diff --git a/CONTRIBUTING.md b/CONTRIBUTING.md index 77bc9da6..8bb8a23d 100644 --- a/CONTRIBUTING.md +++ b/CONTRIBUTING.md @@ -76,6 +76,11 @@ Below is a sample of how additional vehicle directories should be created. - Code should conform to the [coding standard](#oscc-coding-standard) - Push your changes to a topic branch in your branch of the repository +- Ideally, your commits would also be [GPG signed](https://help.github.com/articles/signing-commits-using-gpg/) + - `git config --global commit.gpgSign true` + - `git config --global gpg.program gpg2` + - `git config --global push.gpgSign if-asked` + - `git config --global user.signingKey ` - Submit a pull request to the repository in the PolySync organization - Update your github issue to mark that you have submitted code and are ready for it to be reviewed (Status: Ready for Merge) - Include a link to the pull request in the ticket @@ -197,6 +202,12 @@ Any changes to the OSCC modules must undergo a series of tests that conclude wit 4. The regression test suite completes successfully 5. The [system acceptance tests](#system-acceptance-testing) completes successfully (system acceptance test listed below, some parts automated) - Once all the status checks have passed, resolve any merge conflicts and merge the changed branch with devel + 1. The merge commit will need to be signed, which means local, command-line + merge rather than GitHub UI. + 2. The [hub](https://hub.github.com/) tool can help with this. + 3. `git checkout devel` + 4. `hub merge --no-ff https://github.com/PolySync/oscc/pull/169` + 5. `git push origin devel` ## System Acceptance Testing diff --git a/Jenkinsfile b/Jenkinsfile index 506e37a7..4e566ff0 100644 --- a/Jenkinsfile +++ b/Jenkinsfile @@ -10,24 +10,32 @@ node('arduino') { ]) } stage('Build') { - parallel 'kia soul firmware': { - sh 'cd firmware && mkdir build && cd build && cmake .. -DKIA_SOUL=ON -DCMAKE_BUILD_TYPE=Release && make' + parallel 'kia soul petrol firmware': { + sh 'cd firmware && mkdir build_kia_soul_petrol && cd build_kia_soul_petrol && cmake .. -DKIA_SOUL=ON -DCMAKE_BUILD_TYPE=Release && make' + }, 'kia soul EV firmware': { + sh 'cd firmware && mkdir build_kia_soul_ev && cd build_kia_soul_ev && cmake .. -DKIA_SOUL_EV=ON -DCMAKE_BUILD_TYPE=Release && make' } echo 'Build Complete!' } - stage('Test') { - parallel 'unit tests': { - sh 'cd firmware && mkdir build_unit_tests && cd build_unit_tests && cmake .. -DKIA_SOUL=ON -DTESTS=ON -DCMAKE_BUILD_TYPE=Release && make run-unit-tests' - echo 'Unit Tests Complete!' - }, 'property-based tests': { - sh 'cd firmware && mkdir build_property_tests && cd build_property_tests && cmake .. -DKIA_SOUL=ON -DTESTS=ON -DCMAKE_BUILD_TYPE=Release && make run-property-tests' - echo 'Property-Based Tests Complete!' - }, 'acceptance tests': { - echo 'Acceptance Tests Complete!' + stage('Kia Soul Petrol Tests') { + parallel 'kia soul petrol unit tests': { + sh 'cd firmware && mkdir build_kia_soul_petrol_unit_tests && cd build_kia_soul_petrol_unit_tests && cmake .. -DKIA_SOUL=ON -DTESTS=ON -DCMAKE_BUILD_TYPE=Release && make run-unit-tests' + echo 'Kia Soul Petrol Unit Tests Complete!' + }, 'kia soul petrol property-based tests': { + sh 'cd firmware && mkdir build_kia_soul_petrol_property_tests && cd build_kia_soul_petrol_property_tests && cmake .. -DKIA_SOUL=ON -DTESTS=ON -DCMAKE_BUILD_TYPE=Release && make run-property-tests' + echo 'Kia Soul Petrol Property-Based Tests Complete!' } + echo 'Kia Soul Petrol Tests Complete!' } - stage('Release') { - echo 'Release Package Created!' + stage('Kia Soul EV Tests') { + parallel 'kia soul ev unit tests': { + sh 'cd firmware && mkdir build_kia_soul_ev_unit_tests && cd build_kia_soul_ev_unit_tests && cmake .. -DKIA_SOUL_EV=ON -DTESTS=ON -DCMAKE_BUILD_TYPE=Release && make run-unit-tests' + echo 'Kia Soul EV Unit Tests Complete!' + }, 'kia soul ev property-based tests': { + sh 'cd firmware && mkdir build_kia_soul_ev_property_tests && cd build_kia_soul_ev_property_tests && cmake .. -DKIA_SOUL_EV=ON -DTESTS=ON -DCMAKE_BUILD_TYPE=Release && make run-property-tests' + echo 'Kia Soul EV Property-Based Tests Complete!' + } + echo 'Kia Soul EV Tests Complete!' } } catch(Exception e) { diff --git a/README.md b/README.md index 3ee0d2ff..978412e0 100644 --- a/README.md +++ b/README.md @@ -9,51 +9,47 @@ Although we currently support only the 2014 or later Kia Soul (w/ Kia Soul EV & Our [Wiki](https://github.com/PolySync/OSCC/wiki) is in the process of being updated to reflect the new changes, but contains a bunch of valuable information to help you get started in understanding the details of the system. +# Versions -## Repository Contents +New versions of the API and the firmware are released periodically as new features are added and bugs are +fixed. **It is of vital importance that you update whenever there is a new version so that you can be certain +you are not using a version with known safety issues.** -* **api** - Software API, so your program can seamlessly talk to our modules. -* **firmware** - Arduino libraries and firmware for the OSCC modules. -* **hardware** - PCB schematics and board designs for control modules. +There are four versions to be aware of: +* **Sensor Interface Board (throttle and steering):** the version is printed on the front of the shield -## Boards +* **Vehicle Control Module (EV brakes):** the version is printed on the front of the shield -The sensor interface and actuator control board schematics and design files are located in the -`hardware/boards` directory. If you don't have the time or fabrication resources, the boards can be -purchased as a kit from the [OSCC website](http://oscc.io). +* **Actuator Control Board (petrol brakes):** the version is printed on the front of the shield -Thanks to [Trey German](https://www.polymorphiclabs.com) and [Macrofab](https://macrofab.com/) for -help designing and manufacturing the custom boards. +* **API and Firmware:** a single version is shared by both and listed in the [Releases section](https://github.com/PolySync/oscc/releases) of the repository. -## Compatibility +The following table can be used to ensure that you use the appropriate firmware version with your boards: -Your hardware version is printed on the front of the OSCC shield. +| | Board Version | Firmware Version | +| ---------------------- | ------------- | ---------------- | +| Sensor Interface | >= 1.0.0 | >= 1.0.0 | +| Vehicle Control | 0.1.0 | >= 1.1.0 | +| Actuator Control | >= 1.2.0 | >= 1.0.0 | +| | < 1.2.0 __*__ | >= 1.0.1 | -### Kia Soul (2014-2017) +__*__ *Later versions of the Actuator Control Board utilize new pins to perform additional safety checks on startup. To use the new firmware on older boards, please see additional instructions in the [build](#brake-startup-test) section.* -#### Steering (Sensor Interface Board) -| Board Version | Firmware Version | -| ------------- | ---------------- | -| >= 1.0.0 | >= 1.0.0 | +# Repository Contents -#### CAN Gateway (Sensor Interface Board) -| Board Version | Firmware Version | -| ------------- | ---------------- | -| >= 1.0.0 | >= 1.0.0 | +* **api** - Software API, so your program can seamlessly talk to our modules. +* **firmware** - Arduino libraries and firmware for the OSCC modules. +* **hardware** - PCB schematics and board designs for control modules. -#### Throttle (Sensor Interface Board) -| Board Version | Firmware Version | -| ------------- | ---------------- | -| >= 1.0.0 | >= 1.0.0 | +# Boards -#### Brake (Actuator Control Board) -| Board Version | Firmware Version | -| ------------- | ---------------- | -| 1.0.0 - 1.0.1 | >= 1.0.1 __*__ | -| >= 1.0.0 | >= 1.0.0 | +The sensor interface and actuator control board schematics and design files are located in the +`hardware/boards` directory. If you don't have the time or fabrication resources, the boards can be +purchased as a kit from the [OSCC website](http://oscc.io). -__*__ *Later versions of the actuator control board utilize new pins to perform additional safety checks on startup. To use the new firmware on older models, please see additional instructions in the [build](#startup-test) section.* +Thanks to [Trey German](https://www.polymorphiclabs.com) and [Macrofab](https://macrofab.com/) for +help designing and manufacturing the custom boards. # Building and Uploading Firmware @@ -68,7 +64,7 @@ You must have Arduino Core and CMake (version 2.8 or greater) installed on your machine. ``` -sudo apt install arduino-core cmake +sudo apt install arduino-core build-essential cmake ``` OSCC uses CMake to avoid some of the limitations of the Arduino IDE. Using this method you can build @@ -86,13 +82,24 @@ mkdir build cd build ``` -To generate Makefiles, tell CMake which platform to build firmware for. For example, if you want to build +To generate Makefiles, tell `cmake` which platform to build firmware for. For example, if you want to build firmware for the Kia Soul: ``` cmake .. -DKIA_SOUL=ON ``` +**Operator Overrides: While all OSCC modules have operator override detection enabled by default, attempting to grab the steering wheel while the system is active could result in serious injury. The preferred method of operator override for steering is to utilize the brake pedal or E-stop button. To disable operator override for the steering module, pass an additional flag to the CMake build step.** + +``` +cmake .. -DKIA_SOUL=ON -DSTEERING_OVERRIDE=OFF +``` + +If steering operator overrides remain enabled, the sensitivity can be adjusted by changing the value of the `TORQUE_DIFFERENCE_OVERRIDE_THRESHOLD` in the corresponding vehicle's header file. + +* Lowering this value will make the steering module more sensitive to operator override, but will result in false positives around high-torque areas, such as the mechanical limits of the steering rack or when quickly and rapidly changing direction. +* Increasing this value will result in fewer false positives, but will make it more difficult to manually override the wheel. + By default, your firmware will have debug symbols which is good for debugging but increases the size of the firmware significantly. To compile without debug symbols and optimizations enabled, use the following instead: @@ -101,7 +108,9 @@ enabled, use the following instead: cmake .. -DKIA_SOUL=ON -DCMAKE_BUILD_TYPE=Release ``` -*For older (< 1.1.0) versions of the actuator control board, you need to set an additional flag using `cmake .. -DKIA_SOUL=ON -DBRAKE_STARTUP_TEST=OFF` to disable startup tests that are not compatible with the previous board design.* + +**NOTE:** +> For older (< 1.2.0) versions of the actuator control board, you need to set an additional flag using `cmake .. -DKIA_SOUL=ON -DBRAKE_STARTUP_TEST=OFF` to disable startup tests that are not compatible with the previous board design. This will generate the necessary files for building. @@ -116,7 +125,7 @@ If you'd like to build only a specific module, you can provide a target name to ``` make brake -make gateway +make can-gateway make steering make throttle ``` @@ -128,7 +137,7 @@ an Arduino with a USB cable, your machine assigns a serial device to it with the path `/dev/ttyACM#` where `#` is a digit starting at 0 and increasing by one with each additional Arduino connected. -You can upload firmware to a single module or to all modules. By default, CMake +You can upload firmware to a single module or to all modules. By default, `cmake` is configured to expect each module to be `/dev/ttyACM0`, so if you connect a single module to your machine, you can flash it without changing anything: @@ -137,7 +146,7 @@ make throttle-upload ``` However, if you want to flash all modules, you need to change the ports in -CMake for each module to match what they are on your machine. The easiest way +`cmake` for each module to match what they are on your machine. The easiest way is to connect each module in alphabetical order (brake, CAN gateway, steering, throttle) so that they are assigned `/dev/ttyACM0` through `/dev/ttyACM3` in a known order. You can then change the ports during the `cmake ..` step: @@ -170,7 +179,7 @@ you can get it with the following command: sudo apt install screen ``` -You need to enable debug mode with `-DDEBUG=ON` and tell CMake what serial port +You need to enable debug mode with `-DDEBUG=ON` and tell `cmake` what serial port the module you want to monitor is connected to (see [section on uploading](#uploading-the-firmware) for details on the default ports for each module). The default baud rate is `115200` but you can change it: @@ -197,14 +206,104 @@ connection. Be aware that using serial printing can affect the timing of the firmware. You may experience strange behavior while printing that does not occur otherwise. +# Controlling Your Vehicle - an Example Application -## Tests +Now that all your Arduino modules are properly setup, it is time to start sending control commands. +We've created an example application, joystick commander, that uses the OSCC API to interface with the firmware, allowing you to send commands using a game controller and receive reports from the on-board OBD-II CAN. These commands are converted into CAN messages, which the OSCC API sends to the respective Arduino modules and are used to actuate the vehicle. + +[OSCC Joystick Commander](https://github.com/PolySync/oscc-joystick-commander) + +# OSCC API + +**Open and close CAN channel to OSCC Control CAN.** + +```c +oscc_result_t oscc_open( uint channel ); +oscc_result_t oscc_close( uint channel ); +``` + +These methods are the start and end points of using the OSCC API in your application. ```oscc_open``` will open a socket connection +on the specified CAN channel, enabling it to quickly receive reports from and send commands to the firmware modules. +When you are ready to terminate your application, ```oscc_close``` can terminate the connection. + +**NOTE:** +> The OSCC API catches the SIGIO signal which is asserted when a CAN frame is received on the CAN socket, and sets up a SIGIO signal handler +> to forward valid CAN messages to your application. If you have a section of code that is susceptible to conflicts with interrupts, +> you should temporarily block the SIGIO signal for the duration of that section and unblock it afterward. + +**Enable and disable all OSCC modules.** + +```c +oscc_result_t oscc_enable( void ); +oscc_result_t oscc_disable( void ); +``` + +After you have initialized your CAN connection to the firmware modules, these methods can be used to enable or disable the system. This +allows your application to choose when to enable sending commands to the firmware. Although you can only send commands when the system is +enabled, you can receive reports at any time. + +**Publish control command to the corresponding module.** + +```c +oscc_result_t publish_brake_position( double normalized_position ); +oscc_result_t publish_steering_torque( double normalized_torque ); +oscc_result_t publish_throttle_position( double normalized_position ); +``` + +These commands will forward a double value to the specified firmware module. The double values are [0.0, 1.0] for brake and throttle, +and [-1.0, 1.0] for steering where -1.0 is counterclockwise and 1.0 is clockwise. The API will construct the appropriate values to send +as spoofed voltages to the vehicle to achieve the desired state. The API also contains safety checks to ensure no voltages outside of +the vehicle's expected range are sent. + +**NOTE:** +> Each of these functions must be called at least once every 200ms to prevent the modules from detecting a loss of communication to the +> controlling computer (at which point they would disable themselves). + +**Register callback function to handle OSCC report and OBD messages.** + +```c +oscc_result_t subscribe_to_brake_reports( void(*callback)(oscc_brake_report_s *report) ); +oscc_result_t subscribe_to_steering_reports( void(*callback)(oscc_steering_report_s *report) ); +oscc_result_t subscribe_to_throttle_reports( void(*callback)(oscc_throttle_report_s *report) ); +oscc_result_t subscribe_to_fault_reports( void(*callback)(oscc_fault_report_s *report) ); +oscc_result_t subscribe_to_obd_messages( void(*callback)(struct can_frame *frame) ); +``` + +In order to receive reports from the modules, your application will need to register a callback handler with the OSCC API. +When the appropriate report for your callback function is received from the API's socket connection, it will then forward the +report to your software. + +In addition to OSCC specific reports, it will also forward any non-OSCC reports to any callback function registered with +```subscribe_to_obd_messages```. This can be used to view CAN frames received from the vehicle's OBD-II CAN channel. If you know +the corresponding CAN frame's id, you can parse reports sent from the car. + +# Tests There are two types of tests available: unit and property-based. +## Test Dependencies + +The unit tests and property-based tests each have their own set of dependencies +required to run the tests. + +For the unit tests you must have **Cucumber 2.0.0** and its dependency **Boost** installed: + +``` +sudo apt install ruby-dev libboost-dev +sudo gem install cucumber -v 2.0.0 +``` + +For the property-based tests you must have **Rust**, its build manager **Cargo**, and **libclang**: + +``` +sudo apt install rustc cargo clang libclang-dev +``` + +## Running Tests + Building and running the tests is similar to the firmware itself, but you must instead tell -CMake to build the tests instead of the firmware with the `-DTESTS=ON` flag. We also pass -the `-DCMAKE_BUILD_TYPE=Release` flag so that CMake will disable debug symbols and enable +`cmake` to build the tests instead of the firmware with the `-DTESTS=ON` flag. We also pass +the `-DCMAKE_BUILD_TYPE=Release` flag so that `cmake` will disable debug symbols and enable optimizations, good things to do when running tests to ensure nothing breaks with optimizations. Lastly, you must tell the tests which vehicle header to use for the tests (e.g., `-DKIA_SOUL=ON`). @@ -218,22 +317,18 @@ cmake .. -DTESTS=ON -DCMAKE_BUILD_TYPE=Release -DKIA_SOUL=ON ### Unit Tests -Each module has a suite of unit tests that use **Cucumber** with **Cgreen**. There are prebuilt -64-bit Linux versions in `firmware/common/testing/framework`. Boost is required for Cucumber-CPP -and has been statically linked into `libcucumber-cpp.a`. If you need to build your own versions -you can use the provided script `build_test_framework.sh` which will install the Boost dependencies -(needed for building), clone the needed repositories with specific hashes, build the Cgreen and -Cucumber-CPP libraries, and place static Boost in the Cucumber-CPP library. The built will be placed -in an `oscc_test_framework` directory in the directory that you ran the script from. You can then copy -`oscc_test_framework/cucumber-cpp` and `oscc_test_framework/cgreen` to -`firmware/common/testing/framework`. +Each module has a suite of unit tests that use **Cucumber** with **Cgreen**. There are pre-built +64-bit Linux versions in `firmware/common/testing/framework`. -You must have **Cucumber** installed to run the tests: +Boost is required for Cucumber-CPP and has been statically linked into `libcucumber-cpp.a`. +If you need to build your own versions you can use the provided script `build_test_framework.sh` +which will install the Boost dependencies (needed for building), clone the needed +repositories with specific hashes, build the Cgreen and Cucumber-CPP libraries, +and place static Boost in the Cucumber-CPP library. -``` -sudo apt install ruby-dev -sudo gem install cucumber -v 2.0.0 -``` +The built libraries will be placed in an `oscc_test_framework` directory in the +directory that you ran the script from. You can then copy `oscc_test_framework/cucumber-cpp` +and `oscc_test_framework/cgreen` to `firmware/common/testing/framework`. We can run all of the unit tests available: @@ -275,15 +370,11 @@ Feature: Receiving commands | 1024 | 4096 | 4096 | ``` -## Property-Based Tests +### Property-Based Tests The throttle, steering, and brake modules, along with the PID controller library, also contain a series of property-based tests. -These tests use [QuickCheck for Rust](http://burntsushi.net/rustdoc/quickcheck/), so **Rust** and **Cargo** -need to be [installed](https://www.rust-lang.org/en-US/install.html) in order to run them locally. - - We can run all of the property-based tests available: ``` @@ -319,110 +410,21 @@ running 0 tests test result: ok. 0 passed; 0 failed; 0 ignored; 0 measured ``` -### Run All Tests +### All Tests -Finally, you can run all available tests: +Finally, as a convenience you can run all available tests: ``` make run-all-tests ``` - -## Easier CMake Configuration - -If you have a lot of `-D` commands to pass to CMake (e.g., configuring the serial -port and baud rates of all of the modules), you can instead configure with a GUI -using `cmake-gui`: - -``` -sudo apt install cmake-gui -``` - -Then use `cmake-gui` where you would normally use `cmake`: - -``` -cd firmware -mkdir build -cd build -cmake-gui .. -``` - -The GUI will open and you can change all of the options you would normally need -to pass on the command line. First, press the `Configure` button and then press -`Finish` on the dialog that opens. In the main window you'll see a list of -options that you can change that would normally be configured on the command line -with `-D` commands. When you're done, click `Configure` again and then click -the `Generate` button. You can then close `cmake-gui` and run any `make` commands -like you normally would. - -# Controlling Your Vehicle - an Example Application - -Now that all your Arduino modules are properly setup, it is time to start sending control commands. -We've created an example application, joystick commander, that uses the OSCC API to interface with the firmware, allowing you to send commands using a game controller and receive reports from the on-board OBD-II CAN. These commands are converted into CAN messages, which the OSCC API sends to the respective Arduino modules and are used to actuate the vehicle. - -[OSCC Joystick Commander](https://github.com/PolySync/oscc-joystick-commander) - -# OSCC API - -**Use provided CAN channel to open and close communications to CAN bus connected to the OSCC modules.** - -```c -oscc_result_t oscc_open( uint channel ) -oscc_result_t oscc_close( uint ) -``` - -These methods are the start and end points of using the OSCC API in your application. ```oscc_open``` will open a socket connection -on the specified CAN channel, enabling it to quickly receive reports from and send commands to the firmware modules. -When you are ready to terminate your application, ```oscc_close``` can terminate the connection. - -**Send enable or disable commands to all OSCC modules.** - -```c -oscc_result_t oscc_enable( void ) -oscc_result_t oscc_disable( void ) -``` - -After you have initialized your CAN connection to the firmware modules, these methods can be used to enable or disable the system. This -allows your application to choose when to enable sending commands to the firmware. Although you can only send commands when the system is -enabled, you can receive reports at any time. - -**Publish message with requested normalized value to the corresponding module.** - -```c -oscc_result_t publish_brake_position( double normalized_position ) -oscc_result_t publish_steering_torque( double normalized_torque ) -oscc_result_t publish_throttle_position( double normalized_position ) -``` - -These commands will forward a double value, *[0.0, 1.0]*, to the specified firmware module. The API will construct the appropriate values -to send spoof commands into the vehicle ECU's to achieve the desired state. The API also contains safety checks to ensure no invalid values -can be written onto the hardware. - -**Register callback function to be called when OBD message received from vehicle.** - -```c -oscc_result_t subscribe_to_brake_reports( void(*callback)(oscc_brake_report_s *report) ) -oscc_result_t subscribe_to_steering_reports( void(*callback)(oscc_steering_report_s *report) ) -oscc_result_t subscribe_to_throttle_reports( void(*callback)(oscc_throttle_report_s *report) ) -oscc_result_t subscribe_to_fault_reports( void(*callback)(oscc_fault_report_s *report) ) -oscc_result_t subscribe_to_obd_messages( void(*callback)(struct can_frame *frame) ) -``` - -In order to receive reports from the modules, your application will need to register a callback handler with the OSCC API. -When the appropriate report for your callback function is received from the API's socket connection, it will then forward the -report to your software. - -In addition to OSCC specific reports, it will also forward any non-OSCC reports to any callback function registered with -```subscribe_to_obd_messages```. This can be used to view CAN frames received from the vehicle's OBD-II CAN channel. If you know -the corresponding CAN frame's id, you can parse reports sent from the car. - # Additional Vehicles & Contributing OSCC currently has information regarding the Kia Soul PS (2014-2016), but we want to grow! The repository is structured to facilitate including more vehicles as more is learned about them. In order to include information related to a new vehicle's specification, follow the format defined in ```api/include/vehicles/kia_soul.h``` and -add a CMake option to choose your new header when compiling the API. +add a `cmake` option to choose your new header when compiling the API. Please see [CONTRIBUTING.md](CONTRIBUTING.md). diff --git a/api/OsccConfig.cmake b/api/OsccConfig.cmake new file mode 100644 index 00000000..061fb1d1 --- /dev/null +++ b/api/OsccConfig.cmake @@ -0,0 +1,7 @@ +if(KIA_SOUL) + add_definitions(-DKIA_SOUL) +elseif(KIA_SOUL_EV) + add_definitions(-DKIA_SOUL_EV) +else() + message(FATAL_ERROR "No platform selected") +endif() diff --git a/api/include/can_protocols/brake_can_protocol.h b/api/include/can_protocols/brake_can_protocol.h index 33f5d10c..78815aa2 100644 --- a/api/include/can_protocols/brake_can_protocol.h +++ b/api/include/can_protocols/brake_can_protocol.h @@ -13,6 +13,18 @@ #include "magic.h" +/* + * @brief Brake enable message (CAN frame) ID. + * + */ +#define OSCC_BRAKE_ENABLE_CAN_ID (0x50) + +/* + * @brief Brake disable message (CAN frame) ID. + * + */ +#define OSCC_BRAKE_DISABLE_CAN_ID (0x51) + /* * @brief Brake command message (CAN frame) ID. * @@ -43,10 +55,48 @@ */ #define OSCC_BRAKE_DTC_INVALID_SENSOR_VAL (0x0) +/* + * @brief Brake DTC bitfield position indicating an operator override. + * + */ +#define OSCC_BRAKE_DTC_OPERATOR_OVERRIDE (0x1) + #pragma pack(push) #pragma pack(1) +/** + * @brief Brake enable message. + * + * CAN frame ID: \ref OSCC_BRAKE_ENABLE_CAN_ID + * + */ +typedef struct +{ + uint8_t magic[2]; /*!< Magic number identifying CAN frame as from OSCC. + * Byte 0 should be \ref OSCC_MAGIC_BYTE_0. + * Byte 1 should be \ref OSCC_MAGIC_BYTE_1. */ + + uint8_t reserved[6]; /*!< Reserved. */ +} oscc_brake_enable_s; + + +/** + * @brief Brake disable message. + * + * CAN frame ID: \ref OSCC_BRAKE_DISABLE_CAN_ID + * + */ +typedef struct +{ + uint8_t magic[2]; /*!< Magic number identifying CAN frame as from OSCC. + * Byte 0 should be \ref OSCC_MAGIC_BYTE_0. + * Byte 1 should be \ref OSCC_MAGIC_BYTE_1. */ + + uint8_t reserved[6]; /*!< Reserved. */ +} oscc_brake_disable_s; + + /** * @brief Brake command message data. * @@ -55,17 +105,21 @@ */ typedef struct { - uint8_t magic[2]; /* Magic number identifying CAN frame as from OSCC. - Byte 0 should be \ref OSCC_MAGIC_BYTE_0. - Byte 1 should be \ref OSCC_MAGIC_BYTE_1. */ + uint8_t magic[2]; /*!< Magic number identifying CAN frame as from OSCC. + * Byte 0 should be \ref OSCC_MAGIC_BYTE_0. + * Byte 1 should be \ref OSCC_MAGIC_BYTE_1. */ +#if defined(KIA_SOUL) uint16_t pedal_command; /*!< Pedal command. [65535 == 100%] */ - uint8_t enable; /*!< Command to enable or disable steering control. - * Zero value means disable. - * Non-zero value means enable. */ + uint8_t reserved[4]; /*!< Reserved. */ +#elif defined(KIA_SOUL_EV) + uint16_t spoof_value_low; /*!< Value to be sent on the low spoof signal. */ - uint8_t reserved[3]; /*!< Reserved. */ + uint16_t spoof_value_high; /*!< Value to be sent on the high spoof signal. */ + + uint8_t reserved[2]; /*!< Reserved. */ +#endif } oscc_brake_command_s; @@ -77,9 +131,9 @@ typedef struct */ typedef struct { - uint8_t magic[2]; /* Magic number identifying CAN frame as from OSCC. - Byte 0 should be \ref OSCC_MAGIC_BYTE_0. - Byte 1 should be \ref OSCC_MAGIC_BYTE_1. */ + uint8_t magic[2]; /*!< Magic number identifying CAN frame as from OSCC. + * Byte 0 should be \ref OSCC_MAGIC_BYTE_0. + * Byte 1 should be \ref OSCC_MAGIC_BYTE_1. */ uint8_t enabled; /*!< Braking controls enabled state. * Zero value means disabled (commands are ignored). @@ -90,7 +144,7 @@ typedef struct * Non-zero value means an operator has physically overridden * the system. */ - uint8_t dtcs; /* Bitfield of DTCs present in the module. */ + uint8_t dtcs; /*!< Bitfield of DTCs present in the module. */ uint8_t reserved[3]; /*!< Reserved. */ } oscc_brake_report_s; diff --git a/api/include/can_protocols/fault_can_protocol.h b/api/include/can_protocols/fault_can_protocol.h index b356ee8c..f8922174 100644 --- a/api/include/can_protocols/fault_can_protocol.h +++ b/api/include/can_protocols/fault_can_protocol.h @@ -44,13 +44,15 @@ typedef enum */ typedef struct { - uint8_t magic[2]; /* Magic number identifying CAN frame as from OSCC. - Byte 0 should be \ref OSCC_MAGIC_BYTE_0. - Byte 1 should be \ref OSCC_MAGIC_BYTE_1. */ + uint8_t magic[2]; /*!< Magic number identifying CAN frame as from OSCC. + * Byte 0 should be \ref OSCC_MAGIC_BYTE_0. + * Byte 1 should be \ref OSCC_MAGIC_BYTE_1. */ - uint32_t fault_origin_id; /* ID of the module that is sending out the fault. */ + uint32_t fault_origin_id; /*!< ID of the module that is sending out the fault. */ - uint8_t reserved[2]; /* Reserved */ + uint8_t dtcs; /*!< DTC bitfield of the module that is sending out the fault. */ + + uint8_t reserved; /*!< Reserved */ } oscc_fault_report_s; #pragma pack(pop) diff --git a/api/include/can_protocols/steering_can_protocol.h b/api/include/can_protocols/steering_can_protocol.h index 29a578bf..34dde26c 100644 --- a/api/include/can_protocols/steering_can_protocol.h +++ b/api/include/can_protocols/steering_can_protocol.h @@ -13,6 +13,18 @@ #include "magic.h" +/* + * @brief Steering enable message (CAN frame) ID. + * + */ +#define OSCC_STEERING_ENABLE_CAN_ID (0x54) + +/* + * @brief Steering disable message (CAN frame) ID. + * + */ +#define OSCC_STEERING_DISABLE_CAN_ID (0x55) + /* * @brief Steering command message (CAN frame) ID. * @@ -43,10 +55,48 @@ */ #define OSCC_STEERING_DTC_INVALID_SENSOR_VAL (0x0) +/* + * @brief Steering DTC bitfield position indicating an operator override. + * + */ +#define OSCC_STEERING_DTC_OPERATOR_OVERRIDE (0x1) + #pragma pack(push) #pragma pack(1) +/** + * @brief Steering enable message. + * + * CAN frame ID: \ref OSCC_STEERING_ENABLE_CAN_ID + * + */ +typedef struct +{ + uint8_t magic[2]; /*!< Magic number identifying CAN frame as from OSCC. + * Byte 0 should be \ref OSCC_MAGIC_BYTE_0. + * Byte 1 should be \ref OSCC_MAGIC_BYTE_1. */ + + uint8_t reserved[6]; /*!< Reserved. */ +} oscc_steering_enable_s; + + +/** + * @brief Steering disable message. + * + * CAN frame ID: \ref OSCC_STEERING_DISABLE_CAN_ID + * + */ +typedef struct +{ + uint8_t magic[2]; /*!< Magic number identifying CAN frame as from OSCC. + * Byte 0 should be \ref OSCC_MAGIC_BYTE_0. + * Byte 1 should be \ref OSCC_MAGIC_BYTE_1. */ + + uint8_t reserved[6]; /*!< Reserved. */ +} oscc_steering_disable_s; + + /** * @brief Steering command message data. * @@ -55,19 +105,15 @@ */ typedef struct { - uint8_t magic[2]; /* Magic number identifying CAN frame as from OSCC. - Byte 0 should be \ref OSCC_MAGIC_BYTE_0. - Byte 1 should be \ref OSCC_MAGIC_BYTE_1. */ + uint8_t magic[2]; /*!< Magic number identifying CAN frame as from OSCC. + * Byte 0 should be \ref OSCC_MAGIC_BYTE_0. + * Byte 1 should be \ref OSCC_MAGIC_BYTE_1. */ uint16_t spoof_value_low; /*!< Value to be sent on the low spoof signal. */ uint16_t spoof_value_high; /*!< Value to be sent on the high spoof signal. */ - uint8_t enable; /*!< Command to enable or disable steering control. - * Zero value means disable. - * Non-zero value means enable. */ - - uint8_t reserved; /*!< Reserved. */ + uint8_t reserved[2]; /*!< Reserved. */ } oscc_steering_command_s; @@ -79,9 +125,9 @@ typedef struct */ typedef struct { - uint8_t magic[2]; /* Magic number identifying CAN frame as from OSCC. - Byte 0 should be \ref OSCC_MAGIC_BYTE_0. - Byte 1 should be \ref OSCC_MAGIC_BYTE_1. */ + uint8_t magic[2]; /*!< Magic number identifying CAN frame as from OSCC. + * Byte 0 should be \ref OSCC_MAGIC_BYTE_0. + * Byte 1 should be \ref OSCC_MAGIC_BYTE_1. */ uint8_t enabled; /*!< Steering controls enabled state. * Zero value means disabled (commands are ignored). @@ -92,7 +138,7 @@ typedef struct * Non-zero value means an operator has physically overridden * the system. */ - uint8_t dtcs; /* Bitfield of DTCs present in the module. */ + uint8_t dtcs; /*!< Bitfield of DTCs present in the module. */ uint8_t reserved[3]; /*!< Reserved. */ } oscc_steering_report_s; diff --git a/api/include/can_protocols/throttle_can_protocol.h b/api/include/can_protocols/throttle_can_protocol.h index 64ea0192..4eb82200 100644 --- a/api/include/can_protocols/throttle_can_protocol.h +++ b/api/include/can_protocols/throttle_can_protocol.h @@ -13,44 +13,89 @@ #include "magic.h" +/* + * @brief Throttle enable message (CAN frame) ID. + * + */ +#define OSCC_THROTTLE_ENABLE_CAN_ID (0x52) + +/* + * @brief Throttle disable message (CAN frame) ID. + * + */ +#define OSCC_THROTTLE_DISABLE_CAN_ID (0x53) + /* * @brief Throttle command message (CAN frame) ID. * */ #define OSCC_THROTTLE_COMMAND_CAN_ID (0x62) - /* * @brief Throttle report message (CAN frame) ID. * */ #define OSCC_THROTTLE_REPORT_CAN_ID (0x63) - /* * @brief Throttle report message (CAN frame) length. * */ #define OSCC_THROTTLE_REPORT_CAN_DLC (8) - /* * @brief Throttle report message publishing frequency. [Hz] * */ #define OSCC_REPORT_THROTTLE_PUBLISH_FREQ_IN_HZ (50) - /* * @brief Throttle DTC bitfield position indicating an invalid sensor value. * */ #define OSCC_THROTTLE_DTC_INVALID_SENSOR_VAL (0x0) +/* + * @brief Throttle DTC bitfield position indicating an operator override. + * + */ + #define OSCC_THROTTLE_DTC_OPERATOR_OVERRIDE (0x1) + #pragma pack(push) #pragma pack(1) +/** + * @brief Throttle enable message. + * + * CAN frame ID: \ref OSCC_THROTTLE_ENABLE_CAN_ID + * + */ +typedef struct +{ + uint8_t magic[2]; /*!< Magic number identifying CAN frame as from OSCC. + * Byte 0 should be \ref OSCC_MAGIC_BYTE_0. + * Byte 1 should be \ref OSCC_MAGIC_BYTE_1. */ + + uint8_t reserved[6]; /*!< Reserved. */ +} oscc_throttle_enable_s; + + +/** + * @brief Throttle disable message. + * + * CAN frame ID: \ref OSCC_THROTTLE_DISABLE_CAN_ID + * + */ +typedef struct +{ + uint8_t magic[2]; /*!< Magic number identifying CAN frame as from OSCC. + * Byte 0 should be \ref OSCC_MAGIC_BYTE_0. + * Byte 1 should be \ref OSCC_MAGIC_BYTE_1. */ + + uint8_t reserved[6]; /*!< Reserved. */ +} oscc_throttle_disable_s; + /** * @brief Throttle command message. @@ -60,19 +105,15 @@ */ typedef struct { - uint8_t magic[2]; /* Magic number identifying CAN frame as from OSCC. - Byte 0 should be \ref OSCC_MAGIC_BYTE_0. - Byte 1 should be \ref OSCC_MAGIC_BYTE_1. */ + uint8_t magic[2]; /*!< Magic number identifying CAN frame as from OSCC. + * Byte 0 should be \ref OSCC_MAGIC_BYTE_0. + * Byte 1 should be \ref OSCC_MAGIC_BYTE_1. */ uint16_t spoof_value_low; /*!< Value to be sent on the low spoof signal. */ uint16_t spoof_value_high; /*!< Value to be sent on the high spoof signal. */ - uint8_t enable; /*!< Command to enable or disable throttle control. - * Zero value means disable. - * Non-zero value means enable. */ - - uint8_t reserved; /*!< Reserved. */ + uint8_t reserved[2]; /*!< Reserved. */ } oscc_throttle_command_s; @@ -84,11 +125,11 @@ typedef struct */ typedef struct { - uint8_t magic[2]; /* Magic number identifying CAN frame as from OSCC. - Byte 0 should be \ref OSCC_MAGIC_BYTE_0. - Byte 1 should be \ref OSCC_MAGIC_BYTE_1. */ + uint8_t magic[2]; /*!< Magic number identifying CAN frame as from OSCC. + * Byte 0 should be \ref OSCC_MAGIC_BYTE_0. + * Byte 1 should be \ref OSCC_MAGIC_BYTE_1. */ - uint8_t enabled; /*!< Steering controls enabled state. + uint8_t enabled; /*!< Throttle controls enabled state. * Zero value means disabled (commands are ignored). * Non-zero value means enabled (commands are sent to the vehicle). */ @@ -97,7 +138,7 @@ typedef struct * Non-zero value means an operator has physically overridden * the system. */ - uint8_t dtcs; /* Bitfield of DTCs present in the module. */ + uint8_t dtcs; /*!< Bitfield of DTCs present in the module. */ uint8_t reserved[3]; /*!< Reserved. */ } oscc_throttle_report_s; diff --git a/api/include/oscc.h b/api/include/oscc.h index 57a81c96..39c06314 100644 --- a/api/include/oscc.h +++ b/api/include/oscc.h @@ -8,12 +8,14 @@ #ifndef _OSCC_H #define _OSCC_H -#include + #include + #include "can_protocols/brake_can_protocol.h" #include "can_protocols/fault_can_protocol.h" -#include "can_protocols/throttle_can_protocol.h" #include "can_protocols/steering_can_protocol.h" +#include "can_protocols/throttle_can_protocol.h" +#include "vehicles.h" typedef enum diff --git a/api/include/vehicles.h b/api/include/vehicles.h index a236d8d5..32439604 100644 --- a/api/include/vehicles.h +++ b/api/include/vehicles.h @@ -9,8 +9,10 @@ #define _OSCC_VEHICLES_H_ -#ifdef KIA_SOUL -#include "vehicles/kia_soul.h" +#if defined(KIA_SOUL) +#include "vehicles/kia_soul_petrol.h" +#elif defined(KIA_SOUL_EV) +#include "vehicles/kia_soul_ev.h" #endif diff --git a/api/include/vehicles/kia_soul_ev.dbc b/api/include/vehicles/kia_soul_ev.dbc new file mode 100644 index 00000000..87304cf1 --- /dev/null +++ b/api/include/vehicles/kia_soul_ev.dbc @@ -0,0 +1,109 @@ +VERSION "" + +NS_ : + BA_ + BA_DEF_ + BA_DEF_DEF_ + BA_DEF_DEF_REL_ + BA_DEF_REL_ + BA_DEF_SGTYPE_ + BA_REL_ + BA_SGTYPE_ + BO_TX_BU_ + BU_BO_REL_ + BU_EV_REL_ + BU_SG_REL_ + CAT_ + CAT_DEF_ + CM_ + ENVVAR_DATA_ + EV_DATA_ + FILTER + NS_DESC_ + SGTYPE_ + SGTYPE_VAL_ + SG_MUL_VAL_ + SIGTYPE_VALTYPE_ + SIG_GROUP_ + SIG_TYPE_REF_ + SIG_VALTYPE_ + VAL_ + VAL_TABLE_ + +BS_: + +BU_: BRAKE STEERING THROTTLE FAULT + +BO_ 80 BRAKE_ENABLE: 8 BRAKE + SG_ BRAKE_ENABLE_magic : 0|16@1+ (1,0) [0|0] "" BRAKE + SG_ BRAKE_ENABLE_reserved : 16|48@1+ (1,0) [0|0] "" BRAKE + +BO_ 81 BRAKE_DISABLE: 8 BRAKE + SG_ BRAKE_DISABLE_magic : 0|16@1+ (1,0) [0|0] "" BRAKE + SG_ BRAKE_DISABLE_reserved : 16|48@1+ (1,0) [0|0] "" BRAKE + +BO_ 96 BRAKE_COMMAND: 8 BRAKE + SG_ BRAKE_COMMAND_magic : 0|16@1+ (1,0) [0|0] "" BRAKE + SG_ BRAKE_COMMAND_spoof_low : 16|16@1+ (1,0) [0|0] "" BRAKE + SG_ BRAKE_COMMAND_spoof_high : 32|16@1+ (1,0) [0|0] "" BRAKE + SG_ BRAKE_COMMAND_reserved : 48|16@1+ (1,0) [0|0] "" BRAKE + +BO_ 97 BRAKE_REPORT: 8 BRAKE + SG_ BRAKE_REPORT_magic : 0|16@1+ (1,0) [0|0] "" BRAKE + SG_ BRAKE_REPORT_enabled : 16|8@1+ (1,0) [0|0] "" BRAKE + SG_ BRAKE_REPORT_operator_override : 24|8@1+ (1,0) [0|0] "" BRAKE + SG_ BRAKE_REPORT_dtcs : 32|8@1+ (1,0) [0|0] "" BRAKE + SG_ BRAKE_REPORT_reserved : 40|24@1+ (1,0) [0|0] "" BRAKE + +BO_ 84 STEERING_ENABLE: 8 STEERING + SG_ STEERING_ENABLE_magic : 0|16@1+ (1,0) [0|0] "" STEERING + SG_ STEERING_ENABLE_reserved : 16|48@1+ (1,0) [0|0] "" STEERING + +BO_ 85 STEERING_DISABLE: 8 STEERING + SG_ STEERING_DISABLE_magic : 0|16@1+ (1,0) [0|0] "" STEERING + SG_ STEERING_DISABLE_reserved : 16|48@1+ (1,0) [0|0] "" STEERING + +BO_ 100 STEERING_COMMAND: 8 STEERING + SG_ STEERING_COMMAND_magic : 0|16@1+ (1,0) [0|0] "" STEERING + SG_ STEERING_COMMAND_spoof_low : 16|16@1+ (1,0) [0|0] "" STEERING + SG_ STEERING_COMMAND_spoof_high : 32|16@1+ (1,0) [0|0] "" STEERING + SG_ STEERING_COMMAND_reserved : 48|16@1+ (1,0) [0|0] "" STEERING + +BO_ 101 STEERING_REPORT: 8 STEERING + SG_ STEERING_REPORT_magic : 0|16@1+ (1,0) [0|0] "" STEERING + SG_ STEERING_REPORT_enabled : 16|8@1+ (1,0) [0|0] "" STEERING + SG_ STEERING_REPORT_operator_override : 24|8@1+ (1,0) [0|0] "" STEERING + SG_ STEERING_REPORT_dtcs : 32|8@1+ (1,0) [0|0] "" STEERING + SG_ STEERING_REPORT_reserved : 40|24@1+ (1,0) [0|0] "" STEERING + +BO_ 82 THROTTLE_ENABLE: 8 THROTTLE + SG_ THROTTLE_ENABLE_magic : 0|16@1+ (1,0) [0|0] "" THROTTLE + SG_ THROTTLE_ENABLE_reserved : 16|48@1+ (1,0) [0|0] "" THROTTLE + +BO_ 83 THROTTLE_DISABLE: 8 THROTTLE + SG_ THROTTLE_DISABLE_magic : 0|16@1+ (1,0) [0|0] "" THROTTLE + SG_ THROTTLE_DISABLE_reserved : 16|48@1+ (1,0) [0|0] "" THROTTLE + +BO_ 98 THROTTLE_COMMAND: 8 THROTTLE + SG_ THROTTLE_COMMAND_magic : 0|16@1+ (1,0) [0|0] "" THROTTLE + SG_ THROTTLE_COMMAND_spoof_low : 16|16@1+ (1,0) [0|0] "" THROTTLE + SG_ THROTTLE_COMMAND_spoof_high : 32|16@1+ (1,0) [0|0] "" THROTTLE + SG_ THROTTLE_COMMAND_reserved : 48|16@1+ (1,0) [0|0] "" THROTTLE + +BO_ 99 THROTTLE_REPORT: 8 THROTTLE + SG_ THROTTLE_REPORT_magic : 0|16@1+ (1,0) [0|0] "" THROTTLE + SG_ THROTTLE_REPORT_enabled : 16|8@1+ (1,0) [0|0] "" THROTTLE + SG_ THROTTLE_REPORT_operator_override : 24|8@1+ (1,0) [0|0] "" THROTTLE + SG_ THROTTLE_REPORT_dtcs : 32|8@1+ (1,0) [0|0] "" THROTTLE + SG_ THROTTLE_REPORT_reserved : 40|24@1+ (1,0) [0|0] "" THROTTLE + +BO_ 153 FAULT_REPORT: 8 FAULT + SG_ FAULT_REPORT_magic : 0|16@1+ (1,0) [0|0] "" FAULT + SG_ FAULT_REPORT_fault_origin_id : 16|32@1+ (1,0) [0|0] "" FAULT + SG_ FAULT_REPORT_dtcs : 48|8@1+ (1,0) [0|0] "" FAULT + SG_ FAULT_REPORT_reserved : 56|8@1+ (1,0) [0|0] "" FAULT + +CM_ BU_ BRAKE "The OSCC brake module"; +CM_ BU_ STEERING "The OSCC steering module"; +CM_ BU_ THROTTLE "The OSCC throttle module"; +CM_ BU_ FAULT "The OSCC fault report"; diff --git a/api/include/vehicles/kia_soul_ev.h b/api/include/vehicles/kia_soul_ev.h new file mode 100644 index 00000000..e960fbe4 --- /dev/null +++ b/api/include/vehicles/kia_soul_ev.h @@ -0,0 +1,420 @@ +/** + * @file kia_soul.h + * @brief Kia Soul specific macros. + * + */ + + +#ifndef _KIA_SOUL_PLATFORM_INFO_H_ +#define _KIA_SOUL_PLATFORM_INFO_H_ + + +#include + + +// ******************************************************************** +// +// WARNING +// +// The values listed here are carefully tested to ensure that the vehicle's +// components are not actuated outside of the range of what they can handle. +// By changing any of these values you risk attempting to actuate outside of the +// vehicle's valid range. This can cause damage to the hardware and/or a +// vehicle fault. Clearing this fault state requires additional tools. +// +// It is NOT recommended to modify any of these values without expert knowledge. +// +// ************************************************************************ + + +// **************************************************************************** +// OBD MESSAGES +// **************************************************************************** + +/* + * @brief ID of the Kia Soul's OBD steering wheel angle CAN frame. + * + */ +#define KIA_SOUL_OBD_STEERING_WHEEL_ANGLE_CAN_ID ( 0x2B0 ) + +/* + * @brief ID of the Kia Soul's OBD wheel speed CAN frame. + * + */ +#define KIA_SOUL_OBD_WHEEL_SPEED_CAN_ID ( 0x4B0 ) + +/* + * @brief ID of the Kia Soul's OBD brake pressure CAN frame. + * + */ +#define KIA_SOUL_OBD_BRAKE_PRESSURE_CAN_ID ( 0x220 ) + +/* + * @brief Factor to scale OBD steering angle to degrees + * + */ +#define KIA_SOUL_OBD_STEERING_ANGLE_SCALAR ( 0.1 ) + +/** + * @brief Steering wheel angle message data. + * + */ +typedef struct +{ + int16_t steering_wheel_angle; /* 1/10 degrees */ + + uint8_t reserved[6]; /* Reserved. */ +} kia_soul_obd_steering_wheel_angle_data_s; + +/** + * @brief Wheel speed message data. + * + */ +typedef struct +{ + int16_t wheel_speed_front_left; /* 1/50 mph */ + + int16_t wheel_speed_front_right; /* 1/50 mph */ + + int16_t wheel_speed_rear_left; /* 1/50 mph */ + + int16_t wheel_speed_rear_right; /* 1/50 mph */ +} kia_soul_obd_wheel_speed_data_s; + +/** + * @brief Brake pressure message data. + * + */ +typedef struct +{ + int16_t master_cylinder_pressure; /* 1/10th of a bar per bit */ + + uint8_t reserved[6]; /* Reserved. */ +} kia_soul_obd_brake_pressure_data_s; + + + /* + * @brief Number of steps per volt corresponding to 4096 steps (2^12) across 5 volts. + * + */ +#define STEPS_PER_VOLT ( 819.2 ) + + + + +// **************************************************************************** +// BRAKE MODULE +// **************************************************************************** + +/* + * @brief Minimum allowable brake value. + * + */ +#define MINIMUM_BRAKE_COMMAND ( 0.0 ) + +/* + * @brief Maximum allowable brake value. + * + */ +#define MAXIMUM_BRAKE_COMMAND ( 1.0 ) + +/* + * @brief Minimum allowed voltage for the low spoof signal voltage. [volts] + * + */ +#define BRAKE_SPOOF_LOW_SIGNAL_VOLTAGE_MIN ( 0.303 ) + +/* + * @brief Maximum allowed voltage for the low spoof signal voltage. [volts] + * + */ +#define BRAKE_SPOOF_LOW_SIGNAL_VOLTAGE_MAX ( 1.40 ) + +/** + * @brief Minimum allowed voltage for the high spoof signal voltage. [volts] + * + */ +#define BRAKE_SPOOF_HIGH_SIGNAL_VOLTAGE_MIN ( 0.635 ) + +/** + * @brief Maximum allowed voltage for the high spoof signal voltage. [volts] + * + */ +#define BRAKE_SPOOF_HIGH_SIGNAL_VOLTAGE_MAX ( 2.87 ) + +/* + * @brief Minimum allowed value for the low spoof signal value. [steps] + * + * Equal to \ref BRAKE_SPOOF_LOW_SIGNAL_VOLTAGE_MIN * \ref STEPS_PER_VOLT. + */ +#define BRAKE_SPOOF_LOW_SIGNAL_RANGE_MIN ( 249 ) + +/* + * @brief Minimum allowed value for the low spoof signal value. [steps] + * + * Equal to \ref BRAKE_SPOOF_LOW_SIGNAL_VOLTAGE_MAX * \ref STEPS_PER_VOLT. + */ +#define BRAKE_SPOOF_LOW_SIGNAL_RANGE_MAX ( 1146 ) + +/* + * @brief Minimum allowed value for the low spoof signal value. [steps] + * + * Equal to \ref BRAKE_SPOOF_HIGH_SIGNAL_VOLTAGE_MIN * \ref STEPS_PER_VOLT. + */ +#define BRAKE_SPOOF_HIGH_SIGNAL_RANGE_MIN ( 521 ) + +/* + * @brief Minimum allowed value for the low spoof signal value. [steps] + * + * Equal to \ref BRAKE_SPOOF_HIGH_SIGNAL_VOLTAGE_MAX * \ref STEPS_PER_VOLT. + */ +#define BRAKE_SPOOF_HIGH_SIGNAL_RANGE_MAX ( 2351 ) + +/* + * @brief Calculation to convert a brake position to a low spoof voltage. + * + */ +#define BRAKE_POSITION_TO_VOLTS_LOW( position ) ( (position) *\ + (BRAKE_SPOOF_LOW_SIGNAL_VOLTAGE_MAX - BRAKE_SPOOF_LOW_SIGNAL_VOLTAGE_MIN) +\ + BRAKE_SPOOF_LOW_SIGNAL_VOLTAGE_MIN ) + +/* + * @brief Calculation to convert a brake position to a high spoof voltage. + * + */ +#define BRAKE_POSITION_TO_VOLTS_HIGH( position ) ( (position) *\ + (BRAKE_SPOOF_HIGH_SIGNAL_VOLTAGE_MAX - BRAKE_SPOOF_HIGH_SIGNAL_VOLTAGE_MIN) +\ + BRAKE_SPOOF_HIGH_SIGNAL_VOLTAGE_MIN ) + +/* + * @brief Value of the accelerator position that indicates operator override. [steps] + * + */ +#define BRAKE_PEDAL_OVERRIDE_THRESHOLD ( 130 ) + +/* + * @brief Minimum value of the low spoof signal that activates the brake lights. [steps] + * + */ +#define BRAKE_LIGHT_SPOOF_LOW_THRESHOLD ( 300 ) + +/* + * @brief Minimum value of the high spoof signal that activates the brake lights. [steps] + * + */ +#define BRAKE_LIGHT_SPOOF_HIGH_THRESHOLD ( 600 ) + + + + +// **************************************************************************** +// STEERING MODULE +// **************************************************************************** + +/* + * @brief Minimum allowable torque value. + * + */ +#define MINIMUM_TORQUE_COMMAND ( -12.8 ) + +/* + * @brief Maximum allowable torque value. + * + */ +#define MAXIMUM_TORQUE_COMMAND ( 12.7 ) + +/* + * @brief Minimum allowable steering DAC output. [volts] + * + */ +#define STEERING_SPOOF_LOW_SIGNAL_VOLTAGE_MIN ( 0.80 ) + +/* + * @brief Maximum allowable steering DAC output. [volts] + * + */ +#define STEERING_SPOOF_LOW_SIGNAL_VOLTAGE_MAX ( 4.10 ) + +/* + * @brief Minimum allowable steering DAC output. [volts] + * + */ +#define STEERING_SPOOF_HIGH_SIGNAL_VOLTAGE_MIN ( 0.90 ) + +/* + * @brief Maximum allowable steering DAC output. [volts] + * + */ +#define STEERING_SPOOF_HIGH_SIGNAL_VOLTAGE_MAX ( 4.20 ) + +/* + * @brief Minimum allowed value for the low spoof signal value. [steps] + * + * Equal to \ref STEERING_SPOOF_LOW_SIGNAL_VOLTAGE_MIN * \ref STEPS_PER_VOLT. + */ +#define STEERING_SPOOF_LOW_SIGNAL_RANGE_MIN ( 656 ) + +/* + * @brief Minimum allowed value for the low spoof signal value. [steps] + * + * Equal to \ref STEERING_SPOOF_LOW_SIGNAL_VOLTAGE_MAX * \ref STEPS_PER_VOLT. + */ +#define STEERING_SPOOF_LOW_SIGNAL_RANGE_MAX ( 3358 ) + +/* + * @brief Minimum allowed value for the low spoof signal value. [steps] + * + * Equal to \ref STEERING_SPOOF_HIGH_SIGNAL_VOLTAGE_MIN * \ref STEPS_PER_VOLT. + */ +#define STEERING_SPOOF_HIGH_SIGNAL_RANGE_MIN ( 738 ) + +/* + * @brief Minimum allowed value for the low spoof signal value. [steps] + * + * Equal to \ref STEERING_SPOOF_HIGH_SIGNAL_VOLTAGE_MAX * \ref STEPS_PER_VOLT. + */ +#define STEERING_SPOOF_HIGH_SIGNAL_RANGE_MAX ( 3440 ) + +/* + * @brief Scalar value for the low spoof signal taken from a calibration curve. + * + */ +#define TORQUE_SPOOF_LOW_SIGNAL_CALIBRATION_CURVE_SCALE ( 0.135 ) + +/* + * @brief Offset value for the low spoof signal taken from a calibration curve. + * + */ +#define TORQUE_SPOOF_LOW_SIGNAL_CALIBRATION_CURVE_OFFSET ( 2.39 ) + +/* + * @brief Scalar value for the high spoof signal taken from a calibration curve. + * + */ +#define TORQUE_SPOOF_HIGH_SIGNAL_CALIBRATION_CURVE_SCALE ( -0.145 ) + +/* + * @brief Offset value for the high spoof signal taken from a calibration curve. + * + */ +#define TORQUE_SPOOF_HIGH_SIGNAL_CALIBRATION_CURVE_OFFSET ( 2.42 ) + +/* + * @brief Minimum allowed value for the high spoof signal value. + * + */ +#define STEERING_TORQUE_TO_VOLTS_HIGH( torque ) (\ + ((TORQUE_SPOOF_HIGH_SIGNAL_CALIBRATION_CURVE_SCALE * (torque))\ + + TORQUE_SPOOF_HIGH_SIGNAL_CALIBRATION_CURVE_OFFSET)) + +/* + * @brief Calculation to convert a steering torque to a low spoof value. + * + */ +#define STEERING_TORQUE_TO_VOLTS_LOW( torque ) (\ + ((TORQUE_SPOOF_LOW_SIGNAL_CALIBRATION_CURVE_SCALE * (torque))\ + + TORQUE_SPOOF_LOW_SIGNAL_CALIBRATION_CURVE_OFFSET)) + +/* + * @brief Value of torque sensor difference that indicates likely operator + * override. + * + */ +#define TORQUE_DIFFERENCE_OVERRIDE_THRESHOLD ( 1600 ) + + + + +// **************************************************************************** +// THROTTLE MODULE +// **************************************************************************** + +/* + * @brief Minimum allowable throttle value. + * + */ +#define MINIMUM_THROTTLE_COMMAND ( 0.0 ) + +/* + * @brief Maximum allowable throttle value. + * + */ +#define MAXIMUM_THROTTLE_COMMAND ( 1.0 ) + +/* + * @brief Minimum allowed voltage for the low spoof signal voltage. [volts] + * + */ +#define THROTTLE_SPOOF_LOW_SIGNAL_VOLTAGE_MIN ( 0.30 ) + +/* + * @brief Maximum allowed voltage for the low spoof signal voltage. [volts] + * + */ +#define THROTTLE_SPOOF_LOW_SIGNAL_VOLTAGE_MAX ( 2.00 ) + +/** + * @brief Minimum allowed voltage for the high spoof signal voltage. [volts] + * + */ +#define THROTTLE_SPOOF_HIGH_SIGNAL_VOLTAGE_MIN ( 0.70 ) + +/** + * @brief Maximum allowed voltage for the high spoof signal voltage. [volts] + * + */ +#define THROTTLE_SPOOF_HIGH_SIGNAL_VOLTAGE_MAX ( 4.10 ) + +/* + * @brief Minimum allowed value for the low spoof signal value. [steps] + * + * Equal to \ref THROTTLE_SPOOF_LOW_SIGNAL_VOLTAGE_MIN * \ref STEPS_PER_VOLT. + */ +#define THROTTLE_SPOOF_LOW_SIGNAL_RANGE_MIN ( 245 ) + +/* + * @brief Minimum allowed value for the low spoof signal value. [steps] + * + * Equal to \ref THROTTLE_SPOOF_LOW_SIGNAL_VOLTAGE_MAX * \ref STEPS_PER_VOLT. + */ +#define THROTTLE_SPOOF_LOW_SIGNAL_RANGE_MAX ( 1638 ) + +/* + * @brief Minimum allowed value for the low spoof signal value. [steps] + * + * Equal to \ref THROTTLE_SPOOF_HIGH_SIGNAL_VOLTAGE_MIN * \ref STEPS_PER_VOLT. + */ +#define THROTTLE_SPOOF_HIGH_SIGNAL_RANGE_MIN ( 573 ) + +/* + * @brief Minimum allowed value for the low spoof signal value. [steps] + * + * Equal to \ref THROTTLE_SPOOF_HIGH_SIGNAL_VOLTAGE_MAX * \ref STEPS_PER_VOLT. + */ +#define THROTTLE_SPOOF_HIGH_SIGNAL_RANGE_MAX ( 3358 ) + +/* + * @brief Calculation to convert a throttle position to a low spoof voltage. + * + */ +#define THROTTLE_POSITION_TO_VOLTS_LOW( position ) ( (position) *\ + (THROTTLE_SPOOF_LOW_SIGNAL_VOLTAGE_MAX - THROTTLE_SPOOF_LOW_SIGNAL_VOLTAGE_MIN) +\ + THROTTLE_SPOOF_LOW_SIGNAL_VOLTAGE_MIN ) + +/* + * @brief Calculation to convert a throttle position to a high spoof voltage. + * + */ +#define THROTTLE_POSITION_TO_VOLTS_HIGH( position ) ( (position) *\ + (THROTTLE_SPOOF_HIGH_SIGNAL_VOLTAGE_MAX - THROTTLE_SPOOF_HIGH_SIGNAL_VOLTAGE_MIN) +\ + THROTTLE_SPOOF_HIGH_SIGNAL_VOLTAGE_MIN ) + +/* + * @brief Value of the accelerator position that indicates operator override. [steps] + * + */ +#define ACCELERATOR_OVERRIDE_THRESHOLD ( 185.0 ) + + + +#endif diff --git a/api/include/vehicles/kia_soul_petrol.dbc b/api/include/vehicles/kia_soul_petrol.dbc new file mode 100644 index 00000000..b033effd --- /dev/null +++ b/api/include/vehicles/kia_soul_petrol.dbc @@ -0,0 +1,108 @@ +VERSION "" + +NS_ : + BA_ + BA_DEF_ + BA_DEF_DEF_ + BA_DEF_DEF_REL_ + BA_DEF_REL_ + BA_DEF_SGTYPE_ + BA_REL_ + BA_SGTYPE_ + BO_TX_BU_ + BU_BO_REL_ + BU_EV_REL_ + BU_SG_REL_ + CAT_ + CAT_DEF_ + CM_ + ENVVAR_DATA_ + EV_DATA_ + FILTER + NS_DESC_ + SGTYPE_ + SGTYPE_VAL_ + SG_MUL_VAL_ + SIGTYPE_VALTYPE_ + SIG_GROUP_ + SIG_TYPE_REF_ + SIG_VALTYPE_ + VAL_ + VAL_TABLE_ + +BS_: + +BU_: BRAKE STEERING THROTTLE FAULT + +BO_ 80 BRAKE_ENABLE: 8 BRAKE + SG_ BRAKE_ENABLE_magic : 0|16@1+ (1,0) [0|0] "" BRAKE + SG_ BRAKE_ENABLE_reserved : 16|48@1+ (1,0) [0|0] "" BRAKE + +BO_ 81 BRAKE_DISABLE: 8 BRAKE + SG_ BRAKE_DISABLE_magic : 0|16@1+ (1,0) [0|0] "" BRAKE + SG_ BRAKE_DISABLE_reserved : 16|48@1+ (1,0) [0|0] "" BRAKE + +BO_ 96 BRAKE_COMMAND: 8 BRAKE + SG_ BRAKE_COMMAND_magic : 0|16@1+ (1,0) [0|0] "" BRAKE + SG_ BRAKE_COMMAND_pedal_command : 16|16@1+ (1,0) [0|0] "" BRAKE + SG_ BRAKE_COMMAND_reserved : 32|32@1+ (1,0) [0|0] "" BRAKE + +BO_ 97 BRAKE_REPORT: 8 BRAKE + SG_ BRAKE_REPORT_magic : 0|16@1+ (1,0) [0|0] "" BRAKE + SG_ BRAKE_REPORT_enabled : 16|8@1+ (1,0) [0|0] "" BRAKE + SG_ BRAKE_REPORT_operator_override : 24|8@1+ (1,0) [0|0] "" BRAKE + SG_ BRAKE_REPORT_dtcs : 32|8@1+ (1,0) [0|0] "" BRAKE + SG_ BRAKE_REPORT_reserved : 40|24@1+ (1,0) [0|0] "" BRAKE + +BO_ 84 STEERING_ENABLE: 8 STEERING + SG_ STEERING_ENABLE_magic : 0|16@1+ (1,0) [0|0] "" STEERING + SG_ STEERING_ENABLE_reserved : 16|48@1+ (1,0) [0|0] "" STEERING + +BO_ 85 STEERING_DISABLE: 8 STEERING + SG_ STEERING_DISABLE_magic : 0|16@1+ (1,0) [0|0] "" STEERING + SG_ STEERING_DISABLE_reserved : 16|48@1+ (1,0) [0|0] "" STEERING + +BO_ 100 STEERING_COMMAND: 8 STEERING + SG_ STEERING_COMMAND_magic : 0|16@1+ (1,0) [0|0] "" STEERING + SG_ STEERING_COMMAND_spoof_low : 16|16@1+ (1,0) [0|0] "" STEERING + SG_ STEERING_COMMAND_spoof_high : 32|16@1+ (1,0) [0|0] "" STEERING + SG_ STEERING_COMMAND_reserved : 48|16@1+ (1,0) [0|0] "" STEERING + +BO_ 101 STEERING_REPORT: 8 STEERING + SG_ STEERING_REPORT_magic : 0|16@1+ (1,0) [0|0] "" STEERING + SG_ STEERING_REPORT_enabled : 16|8@1+ (1,0) [0|0] "" STEERING + SG_ STEERING_REPORT_operator_override : 24|8@1+ (1,0) [0|0] "" STEERING + SG_ STEERING_REPORT_dtcs : 32|8@1+ (1,0) [0|0] "" STEERING + SG_ STEERING_REPORT_reserved : 40|24@1+ (1,0) [0|0] "" STEERING + +BO_ 82 THROTTLE_ENABLE: 8 THROTTLE + SG_ THROTTLE_ENABLE_magic : 0|16@1+ (1,0) [0|0] "" THROTTLE + SG_ THROTTLE_ENABLE_reserved : 16|48@1+ (1,0) [0|0] "" THROTTLE + +BO_ 83 THROTTLE_DISABLE: 8 THROTTLE + SG_ THROTTLE_DISABLE_magic : 0|16@1+ (1,0) [0|0] "" THROTTLE + SG_ THROTTLE_DISABLE_reserved : 16|48@1+ (1,0) [0|0] "" THROTTLE + +BO_ 98 THROTTLE_COMMAND: 8 THROTTLE + SG_ THROTTLE_COMMAND_magic : 0|16@1+ (1,0) [0|0] "" THROTTLE + SG_ THROTTLE_COMMAND_spoof_low : 16|16@1+ (1,0) [0|0] "" THROTTLE + SG_ THROTTLE_COMMAND_spoof_high : 32|16@1+ (1,0) [0|0] "" THROTTLE + SG_ THROTTLE_COMMAND_reserved : 48|16@1+ (1,0) [0|0] "" THROTTLE + +BO_ 99 THROTTLE_REPORT: 8 THROTTLE + SG_ THROTTLE_REPORT_magic : 0|16@1+ (1,0) [0|0] "" THROTTLE + SG_ THROTTLE_REPORT_enabled : 16|8@1+ (1,0) [0|0] "" THROTTLE + SG_ THROTTLE_REPORT_operator_override : 24|8@1+ (1,0) [0|0] "" THROTTLE + SG_ THROTTLE_REPORT_dtcs : 32|8@1+ (1,0) [0|0] "" THROTTLE + SG_ THROTTLE_REPORT_reserved : 40|24@1+ (1,0) [0|0] "" THROTTLE + +BO_ 153 FAULT_REPORT: 8 FAULT + SG_ FAULT_REPORT_magic : 0|16@1+ (1,0) [0|0] "" FAULT + SG_ FAULT_REPORT_fault_origin_id : 16|32@1+ (1,0) [0|0] "" FAULT + SG_ FAULT_REPORT_dtcs : 48|8@1+ (1,0) [0|0] "" FAULT + SG_ FAULT_REPORT_reserved : 56|8@1+ (1,0) [0|0] "" FAULT + +CM_ BU_ BRAKE "The OSCC brake module"; +CM_ BU_ STEERING "The OSCC steering module"; +CM_ BU_ THROTTLE "The OSCC throttle module"; +CM_ BU_ FAULT "The OSCC fault report"; diff --git a/api/include/vehicles/kia_soul.h b/api/include/vehicles/kia_soul_petrol.h similarity index 65% rename from api/include/vehicles/kia_soul.h rename to api/include/vehicles/kia_soul_petrol.h index 031c9291..fb75180b 100644 --- a/api/include/vehicles/kia_soul.h +++ b/api/include/vehicles/kia_soul_petrol.h @@ -93,6 +93,11 @@ typedef struct } kia_soul_obd_brake_pressure_data_s; + /* + * @brief Number of steps per volt corresponding to 4096 steps (2^12) across 5 volts. + * + */ +#define STEPS_PER_VOLT ( 819.2 ) // **************************************************************************** @@ -273,94 +278,115 @@ typedef struct // **************************************************************************** /* - * @brief Minimum allowable steering DAC output. [steps] + * @brief Minimum allowable torque value. * */ -#define STEERING_SPOOF_SIGNAL_MIN ( 868.0 ) +#define MINIMUM_TORQUE_COMMAND ( -12.8 ) /* - * @brief Maximum allowable steering DAC output. [steps] + * @brief Maximum allowable torque value. * */ -#define STEERING_SPOOF_SIGNAL_MAX ( 3031.0 ) +#define MAXIMUM_TORQUE_COMMAND ( 12.7 ) /* - * @brief Minimum allowable torque value. + * @brief Minimum allowable steering DAC output. [volts] * */ -#define MINIMUM_TORQUE_COMMAND ( -10 ) +#define STEERING_SPOOF_LOW_SIGNAL_VOLTAGE_MIN ( 0.80 ) /* - * @brief Maximum allowable torque value. + * @brief Maximum allowable steering DAC output. [volts] + * + */ +#define STEERING_SPOOF_LOW_SIGNAL_VOLTAGE_MAX ( 4.10 ) + +/* + * @brief Minimum allowable steering DAC output. [volts] * */ -#define MAXIMUM_TORQUE_COMMAND ( 10 ) +#define STEERING_SPOOF_HIGH_SIGNAL_VOLTAGE_MIN ( 0.90 ) +/* + * @brief Maximum allowable steering DAC output. [volts] + * + */ +#define STEERING_SPOOF_HIGH_SIGNAL_VOLTAGE_MAX ( 4.20 ) - /* - * @brief Number of steps per volt corresponding to 4096 steps across 5 volts. +/* + * @brief Minimum allowed value for the low spoof signal value. [steps] * + * Equal to \ref STEERING_SPOOF_LOW_SIGNAL_VOLTAGE_MIN * \ref STEPS_PER_VOLT. */ -#define STEPS_PER_VOLT ( 819.2 ) +#define STEERING_SPOOF_LOW_SIGNAL_RANGE_MIN ( 656 ) /* - * @brief Scalar value for the low spoof signal taken from a calibration curve. + * @brief Minimum allowed value for the low spoof signal value. [steps] * + * Equal to \ref STEERING_SPOOF_LOW_SIGNAL_VOLTAGE_MAX * \ref STEPS_PER_VOLT. */ -#define TORQUE_SPOOF_LOW_SIGNAL_CALIBRATION_CURVE_SCALE ( 0.05 ) +#define STEERING_SPOOF_LOW_SIGNAL_RANGE_MAX ( 3358 ) /* - * @brief Offset value for the low spoof signal taken from a calibration curve. + * @brief Minimum allowed value for the low spoof signal value. [steps] * + * Equal to \ref STEERING_SPOOF_HIGH_SIGNAL_VOLTAGE_MIN * \ref STEPS_PER_VOLT. */ -#define TORQUE_SPOOF_LOW_SIGNAL_CALIBRATION_CURVE_OFFSET ( 2.5 ) +#define STEERING_SPOOF_HIGH_SIGNAL_RANGE_MIN ( 738 ) /* - * @brief Scalar value for the high spoof signal taken from a calibration curve. + * @brief Minimum allowed value for the low spoof signal value. [steps] * + * Equal to \ref STEERING_SPOOF_HIGH_SIGNAL_VOLTAGE_MAX * \ref STEPS_PER_VOLT. */ -#define TORQUE_SPOOF_HIGH_SIGNAL_CALIBRATION_CURVE_SCALE ( -0.05 ) +#define STEERING_SPOOF_HIGH_SIGNAL_RANGE_MAX ( 3440 ) /* - * @brief Offset value for the high spoof signal taken from a calibration curve. + * @brief Scalar value for the low spoof signal taken from a calibration curve. * */ -#define TORQUE_SPOOF_HIGH_SIGNAL_CALIBRATION_CURVE_OFFSET ( 2.5 ) +#define TORQUE_SPOOF_LOW_SIGNAL_CALIBRATION_CURVE_SCALE ( 0.135 ) /* - * @brief Calculation to convert a steering angle to a high spoof value. + * @brief Offset value for the low spoof signal taken from a calibration curve. * */ -#define STEERING_ANGLE_TO_SPOOF_HIGH( angle ) ( (angle) ) +#define TORQUE_SPOOF_LOW_SIGNAL_CALIBRATION_CURVE_OFFSET ( 2.39 ) /* - * @brief Calculation to convert a steering angle to a low spoof value. + * @brief Scalar value for the high spoof signal taken from a calibration curve. * */ -#define STEERING_ANGLE_TO_SPOOF_LOW( angle ) ( (angle) ) +#define TORQUE_SPOOF_HIGH_SIGNAL_CALIBRATION_CURVE_SCALE ( -0.145 ) + +/* + * @brief Offset value for the high spoof signal taken from a calibration curve. + * + */ +#define TORQUE_SPOOF_HIGH_SIGNAL_CALIBRATION_CURVE_OFFSET ( 2.42 ) /* * @brief Minimum allowed value for the high spoof signal value. * */ -#define STEERING_TORQUE_TO_SPOOF_HIGH( torque ) (STEPS_PER_VOLT\ - * ((TORQUE_SPOOF_HIGH_SIGNAL_CALIBRATION_CURVE_SCALE * (torque))\ +#define STEERING_TORQUE_TO_VOLTS_HIGH( torque ) (\ + ((TORQUE_SPOOF_HIGH_SIGNAL_CALIBRATION_CURVE_SCALE * (torque))\ + TORQUE_SPOOF_HIGH_SIGNAL_CALIBRATION_CURVE_OFFSET)) /* * @brief Calculation to convert a steering torque to a low spoof value. * */ -#define STEERING_TORQUE_TO_SPOOF_LOW( torque ) (STEPS_PER_VOLT\ - * ((TORQUE_SPOOF_LOW_SIGNAL_CALIBRATION_CURVE_SCALE * (torque))\ +#define STEERING_TORQUE_TO_VOLTS_LOW( torque ) (\ + ((TORQUE_SPOOF_LOW_SIGNAL_CALIBRATION_CURVE_SCALE * (torque))\ + TORQUE_SPOOF_LOW_SIGNAL_CALIBRATION_CURVE_OFFSET)) /* - * @brief Value of the torque sensor that indicates operator override. - * [degrees/microsecond] + * @brief Value of torque sensor difference that indicates likely operator + * override. * */ -#define OVERRIDE_WHEEL_THRESHOLD_IN_DEGREES_PER_USEC ( 750 ) +#define TORQUE_DIFFERENCE_OVERRIDE_THRESHOLD ( 1600 ) @@ -373,80 +399,84 @@ typedef struct * @brief Minimum allowable throttle value. * */ -#define MINIMUM_THROTTLE_COMMAND ( 0 ) +#define MINIMUM_THROTTLE_COMMAND ( 0.0 ) /* * @brief Maximum allowable throttle value. * */ -#define MAXIMUM_THROTTLE_COMMAND ( 820 ) +#define MAXIMUM_THROTTLE_COMMAND ( 1.0 ) /* - * @brief Calculation to convert a throttle position to a high spoof value. + * @brief Minimum allowed voltage for the low spoof signal voltage. [volts] * */ -#define THROTTLE_POSITION_TO_SPOOF_HIGH( position ) (STEPS_PER_VOLT\ - * ((THROTTLE_SPOOF_HIGH_SIGNAL_CALIBRATION_CURVE_SCALE * (position))\ - + THROTTLE_SPOOF_HIGH_SIGNAL_CALIBRATION_CURVE_OFFSET)) +#define THROTTLE_SPOOF_LOW_SIGNAL_VOLTAGE_MIN ( 0.30 ) /* - * @brief Calculation to convert a throttle position to a low spoof value. + * @brief Maximum allowed voltage for the low spoof signal voltage. [volts] * */ -#define THROTTLE_POSITION_TO_SPOOF_LOW( position ) (STEPS_PER_VOLT\ - * ((THROTTLE_SPOOF_LOW_SIGNAL_CALIBRATION_CURVE_SCALE * (position))\ - + THROTTLE_SPOOF_LOW_SIGNAL_CALIBRATION_CURVE_OFFSET)) +#define THROTTLE_SPOOF_LOW_SIGNAL_VOLTAGE_MAX ( 2.00 ) -/* - * @brief Minimum allowed value for the low spoof signal value. +/** + * @brief Minimum allowed voltage for the high spoof signal voltage. [volts] * */ -#define THROTTLE_SPOOF_LOW_SIGNAL_RANGE_MIN ( 0 ) +#define THROTTLE_SPOOF_HIGH_SIGNAL_VOLTAGE_MIN ( 0.70 ) -/* - * @brief Maximum allowed value for the low spoof signal value. +/** + * @brief Maximum allowed voltage for the high spoof signal voltage. [volts] * */ -#define THROTTLE_SPOOF_LOW_SIGNAL_RANGE_MAX ( 1800 ) +#define THROTTLE_SPOOF_HIGH_SIGNAL_VOLTAGE_MAX ( 4.10 ) -/** - * @brief Wheel speed message data. +/* + * @brief Minimum allowed value for the low spoof signal value. [steps] * + * Equal to \ref THROTTLE_SPOOF_LOW_SIGNAL_VOLTAGE_MIN * \ref STEPS_PER_VOLT. */ -#define THROTTLE_SPOOF_HIGH_SIGNAL_RANGE_MIN ( 0 ) +#define THROTTLE_SPOOF_LOW_SIGNAL_RANGE_MIN ( 245 ) -/** - * @brief Wheel speed message data. +/* + * @brief Minimum allowed value for the low spoof signal value. [steps] * + * Equal to \ref THROTTLE_SPOOF_LOW_SIGNAL_VOLTAGE_MAX * \ref STEPS_PER_VOLT. */ -#define THROTTLE_SPOOF_HIGH_SIGNAL_RANGE_MAX ( 3500 ) +#define THROTTLE_SPOOF_LOW_SIGNAL_RANGE_MAX ( 1638 ) /* - * @brief Scalar value for the low spoof signal taken from a calibration curve. + * @brief Minimum allowed value for the low spoof signal value. [steps] * + * Equal to \ref THROTTLE_SPOOF_HIGH_SIGNAL_VOLTAGE_MIN * \ref STEPS_PER_VOLT. */ -#define THROTTLE_SPOOF_LOW_SIGNAL_CALIBRATION_CURVE_SCALE (0.0004) +#define THROTTLE_SPOOF_HIGH_SIGNAL_RANGE_MIN ( 573 ) /* - * @brief Offset value for the low spoof signal taken from a calibration curve. + * @brief Minimum allowed value for the low spoof signal value. [steps] * + * Equal to \ref THROTTLE_SPOOF_HIGH_SIGNAL_VOLTAGE_MAX * \ref STEPS_PER_VOLT. */ -#define THROTTLE_SPOOF_LOW_SIGNAL_CALIBRATION_CURVE_OFFSET (0.366) +#define THROTTLE_SPOOF_HIGH_SIGNAL_RANGE_MAX ( 3358 ) /* - * @brief Scalar value for the high spoof signal taken from a calibration curve. + * @brief Calculation to convert a throttle position to a low spoof voltage. * */ -#define THROTTLE_SPOOF_HIGH_SIGNAL_CALIBRATION_CURVE_SCALE (0.0008) +#define THROTTLE_POSITION_TO_VOLTS_LOW( position ) ( (position) *\ + (THROTTLE_SPOOF_LOW_SIGNAL_VOLTAGE_MAX - THROTTLE_SPOOF_LOW_SIGNAL_VOLTAGE_MIN) +\ + THROTTLE_SPOOF_LOW_SIGNAL_VOLTAGE_MIN ) /* - * @brief Offset value for the high spoof signal taken from a calibration curve. + * @brief Calculation to convert a throttle position to a high spoof voltage. * */ -#define THROTTLE_SPOOF_HIGH_SIGNAL_CALIBRATION_CURVE_OFFSET (0.732) +#define THROTTLE_POSITION_TO_VOLTS_HIGH( position ) ( (position) *\ + (THROTTLE_SPOOF_HIGH_SIGNAL_VOLTAGE_MAX - THROTTLE_SPOOF_HIGH_SIGNAL_VOLTAGE_MIN) +\ + THROTTLE_SPOOF_HIGH_SIGNAL_VOLTAGE_MIN ) /* - * @brief Value of the accelerator position that indicates operator override. + * @brief Value of the accelerator position that indicates operator override. [steps] * */ #define ACCELERATOR_OVERRIDE_THRESHOLD ( 185.0 ) diff --git a/api/src/internal/oscc.h b/api/src/internal/oscc.h new file mode 100644 index 00000000..e86edf2e --- /dev/null +++ b/api/src/internal/oscc.h @@ -0,0 +1,62 @@ +/** + * @file internal/oscc.h + * @brief Internal OSCC functionality. + */ + + + #ifndef _OSCC_INTERNAL_H + #define _OSCC_INTERNAL_H + + +#define CONSTRAIN(amt, low, high) ((amt) < (low) ? (low) : ((amt) > (high) ? (high) : (amt))) + + +void (*brake_report_callback)( + oscc_brake_report_s *report ); + +void (*steering_report_callback)( + oscc_steering_report_s *report ); + +void (*throttle_report_callback)( + oscc_throttle_report_s *report ); + +void (*fault_report_callback)( + oscc_fault_report_s *report ); + +void (*obd_frame_callback)( + struct can_frame *frame ); + + +oscc_result_t oscc_init_can( + const char *can_channel ); + +oscc_result_t oscc_can_write( + long id, + void *msg, + unsigned int dlc ); + +oscc_result_t oscc_async_enable( + int socket ); + +oscc_result_t oscc_enable_brakes( + void ); + +oscc_result_t oscc_enable_steering( + void ); + +oscc_result_t oscc_enable_throttle( + void ); + +oscc_result_t oscc_disable_brakes( + void ); + +oscc_result_t oscc_disable_steering( + void ); + +oscc_result_t oscc_disable_throttle( + void ); + +void oscc_update_status( ); + + +#endif /* _OSCC_INTERNAL_H */ diff --git a/api/src/oscc.c b/api/src/oscc.c index 652c07ab..c700ebbc 100644 --- a/api/src/oscc.c +++ b/api/src/oscc.c @@ -1,522 +1,691 @@ +#include +#include +#include +#include +#include #include #include #include -#include -#include -#include #include -#include #include -#include -#include -#include +#include +#include -#include "can_protocols/brake_can_protocol.h" -#include "can_protocols/fault_can_protocol.h" -#include "can_protocols/throttle_can_protocol.h" -#include "can_protocols/steering_can_protocol.h" -#include "vehicles.h" -#include "dtc.h" #include "oscc.h" +#include "internal/oscc.h" -#define CONSTRAIN(amt, low, high) ((amt) < (low) ? (low) : ((amt) > (high) ? (high) : (amt))) - -static int can_socket; -static oscc_brake_command_s brake_cmd; -static oscc_throttle_command_s throttle_cmd; -static oscc_steering_command_s steering_cmd; +static int can_socket = -1; -static void (*steering_report_callback)(oscc_steering_report_s *report); -static void (*brake_report_callback)(oscc_brake_report_s *report); -static void (*throttle_report_callback)(oscc_throttle_report_s *report); -static void (*fault_report_callback)(oscc_fault_report_s *report); -static void (*obd_frame_callback)(struct can_frame *frame); - -static oscc_result_t oscc_init_can( const char *can_channel ); -static oscc_result_t oscc_can_write( long id, void *msg, unsigned int dlc ); -static oscc_result_t oscc_async_enable( int socket ); -static oscc_result_t oscc_enable_brakes( void ); -static oscc_result_t oscc_enable_throttle( void ); -static oscc_result_t oscc_enable_steering( void ); -static oscc_result_t oscc_disable_brakes( void ); -static oscc_result_t oscc_disable_throttle( void ); -static oscc_result_t oscc_disable_steering( void ); -static void oscc_update_status( ); -static void oscc_init_commands( void ); oscc_result_t oscc_open( unsigned int channel ) { - oscc_result_t ret = OSCC_ERROR; + oscc_result_t result = OSCC_ERROR; + - char buffer[16]; + char can_string_buffer[16]; - snprintf( buffer, 16, "can%1d", channel ); + snprintf( can_string_buffer, 16, "can%u", channel ); - printf( "Opening CAN channel: %s\n", buffer ); + printf( "Opening CAN channel: %s\n", can_string_buffer ); - ret = oscc_init_can( buffer ); + result = oscc_init_can( can_string_buffer ); - oscc_init_commands( ); - return ret; + return result; } oscc_result_t oscc_close( unsigned int channel ) { - oscc_result_t ret = OSCC_ERROR; + oscc_result_t result = OSCC_ERROR; - int result = close( can_socket ); - if ( result > 0 ) + if( can_socket != -1 ) { - ret = OSCC_OK; + int result = close( can_socket ); + + if ( result > 0 ) + { + result = OSCC_OK; + } } - return ret; + + return result; } oscc_result_t oscc_enable( void ) { - oscc_result_t ret = oscc_enable_brakes( ); + oscc_result_t result = OSCC_ERROR; + - if (ret == OSCC_OK ) + result = oscc_enable_brakes( ); + + if ( result == OSCC_OK ) { - ret = oscc_enable_throttle( ); + result = oscc_enable_throttle( ); - if (ret == OSCC_OK ) + if (result == OSCC_OK ) { - ret = oscc_enable_steering( ); + result = oscc_enable_steering( ); } } - return ret; + + return result; } oscc_result_t oscc_disable( void ) { - oscc_result_t ret = oscc_disable_brakes( ); + oscc_result_t result = OSCC_ERROR; - if ( ret == OSCC_OK ) + + result = oscc_disable_brakes( ); + + if ( result == OSCC_OK ) { - ret = oscc_disable_throttle( ); + result = oscc_disable_throttle( ); - if ( ret == OSCC_OK ) + if ( result == OSCC_OK ) { - ret = oscc_disable_steering( ); + result = oscc_disable_steering( ); } } - return ret; + + return result; } oscc_result_t oscc_publish_brake_position( double brake_position ) { - oscc_result_t ret = OSCC_ERROR; + oscc_result_t result = OSCC_ERROR; - const double scaled_position = (double) CONSTRAIN ( + + oscc_brake_command_s brake_cmd = + { + .magic[0] = ( uint8_t ) OSCC_MAGIC_BYTE_0, + .magic[1] = ( uint8_t ) OSCC_MAGIC_BYTE_1 + }; + +#if defined(KIA_SOUL) + const double clamped_position = ( double ) CONSTRAIN ( brake_position * MAXIMUM_BRAKE_COMMAND, MINIMUM_BRAKE_COMMAND, MAXIMUM_BRAKE_COMMAND ); - brake_cmd.pedal_command = ( uint16_t ) BRAKE_POSITION_TO_PEDAL( scaled_position ); + brake_cmd.pedal_command = ( uint16_t ) BRAKE_POSITION_TO_PEDAL( clamped_position ); + +#elif defined(KIA_SOUL_EV) + const double clamped_position = CONSTRAIN( + brake_position, + MINIMUM_BRAKE_COMMAND, + MAXIMUM_BRAKE_COMMAND); + + + double spoof_voltage_low = BRAKE_POSITION_TO_VOLTS_LOW( clamped_position ); + + spoof_voltage_low = CONSTRAIN( + spoof_voltage_low, + BRAKE_SPOOF_LOW_SIGNAL_VOLTAGE_MIN, + BRAKE_SPOOF_LOW_SIGNAL_VOLTAGE_MAX); + + + double spoof_voltage_high = BRAKE_POSITION_TO_VOLTS_HIGH( clamped_position ); + + spoof_voltage_high = CONSTRAIN( + spoof_voltage_high, + BRAKE_SPOOF_HIGH_SIGNAL_VOLTAGE_MIN, + BRAKE_SPOOF_HIGH_SIGNAL_VOLTAGE_MAX); + - ret = oscc_can_write( + const uint16_t spoof_value_low = STEPS_PER_VOLT * spoof_voltage_low; + const uint16_t spoof_value_high = STEPS_PER_VOLT * spoof_voltage_high; + + brake_cmd.spoof_value_low = spoof_value_low; + brake_cmd.spoof_value_high = spoof_value_high; +#endif + + result = oscc_can_write( OSCC_BRAKE_COMMAND_CAN_ID, (void *) &brake_cmd, - sizeof( brake_cmd ) ); + sizeof(brake_cmd) ); + - return ret; + return result; } oscc_result_t oscc_publish_throttle_position( double throttle_position ) { - oscc_result_t ret = OSCC_ERROR; + oscc_result_t result = OSCC_ERROR; + + + oscc_throttle_command_s throttle_cmd = + { + .magic[0] = ( uint8_t ) OSCC_MAGIC_BYTE_0, + .magic[1] = ( uint8_t ) OSCC_MAGIC_BYTE_1 + }; + - const double scaled_position = CONSTRAIN( - throttle_position * MAXIMUM_THROTTLE_COMMAND, + const double clamped_position = CONSTRAIN( + throttle_position, MINIMUM_THROTTLE_COMMAND, MAXIMUM_THROTTLE_COMMAND); - uint16_t spoof_value_low = THROTTLE_POSITION_TO_SPOOF_LOW( scaled_position ); - spoof_value_low = CONSTRAIN( - spoof_value_low, - THROTTLE_SPOOF_LOW_SIGNAL_RANGE_MIN, - THROTTLE_SPOOF_LOW_SIGNAL_RANGE_MAX); + double spoof_voltage_low = THROTTLE_POSITION_TO_VOLTS_LOW( clamped_position ); + + spoof_voltage_low = CONSTRAIN( + spoof_voltage_low, + THROTTLE_SPOOF_LOW_SIGNAL_VOLTAGE_MIN, + THROTTLE_SPOOF_LOW_SIGNAL_VOLTAGE_MAX); + + + double spoof_voltage_high = THROTTLE_POSITION_TO_VOLTS_HIGH( clamped_position ); - uint16_t spoof_value_high = THROTTLE_POSITION_TO_SPOOF_HIGH( scaled_position ); + spoof_voltage_high = CONSTRAIN( + spoof_voltage_high, + THROTTLE_SPOOF_HIGH_SIGNAL_VOLTAGE_MIN, + THROTTLE_SPOOF_HIGH_SIGNAL_VOLTAGE_MAX); - spoof_value_high = CONSTRAIN( - spoof_value_high, - THROTTLE_SPOOF_HIGH_SIGNAL_RANGE_MIN, - THROTTLE_SPOOF_HIGH_SIGNAL_RANGE_MAX); + + const uint16_t spoof_value_low = STEPS_PER_VOLT * spoof_voltage_low; + const uint16_t spoof_value_high = STEPS_PER_VOLT * spoof_voltage_high; throttle_cmd.spoof_value_low = spoof_value_low; throttle_cmd.spoof_value_high = spoof_value_high; - ret = oscc_can_write( + result = oscc_can_write( OSCC_THROTTLE_COMMAND_CAN_ID, - (void *)&throttle_cmd, - sizeof(throttle_cmd)); + (void *) &throttle_cmd, + sizeof(throttle_cmd) ); + - return ret; + return result; } oscc_result_t oscc_publish_steering_torque( double torque ) { - oscc_result_t ret = OSCC_ERROR; + oscc_result_t result = OSCC_ERROR; + + + oscc_steering_command_s steering_cmd = + { + .magic[0] = ( uint8_t ) OSCC_MAGIC_BYTE_0, + .magic[1] = ( uint8_t ) OSCC_MAGIC_BYTE_1 + }; - const double scaled_torque = CONSTRAIN( + + const double clamped_torque = CONSTRAIN( torque * MAXIMUM_TORQUE_COMMAND, MINIMUM_TORQUE_COMMAND, MAXIMUM_TORQUE_COMMAND); - uint16_t spoof_value_low = STEERING_TORQUE_TO_SPOOF_LOW( scaled_torque ); - spoof_value_low = CONSTRAIN( - spoof_value_low, - STEERING_SPOOF_SIGNAL_MIN, - STEERING_SPOOF_SIGNAL_MAX); + double spoof_voltage_low = STEERING_TORQUE_TO_VOLTS_LOW( clamped_torque ); + + spoof_voltage_low = CONSTRAIN( + spoof_voltage_low, + STEERING_SPOOF_LOW_SIGNAL_VOLTAGE_MIN, + STEERING_SPOOF_LOW_SIGNAL_VOLTAGE_MAX); + + + double spoof_voltage_high = STEERING_TORQUE_TO_VOLTS_HIGH( clamped_torque ); - uint16_t spoof_value_high = STEERING_TORQUE_TO_SPOOF_HIGH( scaled_torque ); + spoof_voltage_high = CONSTRAIN( + spoof_voltage_high, + STEERING_SPOOF_HIGH_SIGNAL_VOLTAGE_MIN, + STEERING_SPOOF_HIGH_SIGNAL_VOLTAGE_MAX); - spoof_value_high = CONSTRAIN( - spoof_value_high, - STEERING_SPOOF_SIGNAL_MIN, - STEERING_SPOOF_SIGNAL_MAX); + + const uint16_t spoof_value_low = STEPS_PER_VOLT * spoof_voltage_low; + const uint16_t spoof_value_high = STEPS_PER_VOLT * spoof_voltage_high; steering_cmd.spoof_value_low = spoof_value_low; steering_cmd.spoof_value_high = spoof_value_high; - ret = oscc_can_write( + result = oscc_can_write( OSCC_STEERING_COMMAND_CAN_ID, - (void *)&steering_cmd, - sizeof(steering_cmd)); + (void *) &steering_cmd, + sizeof(steering_cmd) ); + - return ret; + return result; } oscc_result_t oscc_subscribe_to_brake_reports( void (*callback)(oscc_brake_report_s *report) ) { - oscc_result_t ret = OSCC_ERROR; + oscc_result_t result = OSCC_ERROR; + if ( callback != NULL ) { brake_report_callback = callback; - ret = OSCC_OK; + result = OSCC_OK; } - return ret; + + return result; } oscc_result_t oscc_subscribe_to_throttle_reports( void (*callback)(oscc_throttle_report_s *report) ) { - oscc_result_t ret = OSCC_ERROR; + oscc_result_t result = OSCC_ERROR; + if ( callback != NULL ) { throttle_report_callback = callback; - ret = OSCC_OK; + result = OSCC_OK; } - return ret; + + return result; } oscc_result_t oscc_subscribe_to_steering_reports( void (*callback)(oscc_steering_report_s *report)) { - oscc_result_t ret = OSCC_ERROR; + oscc_result_t result = OSCC_ERROR; + if ( callback != NULL ) { steering_report_callback = callback; - ret = OSCC_OK; + result = OSCC_OK; } - return ret; + + return result; } oscc_result_t oscc_subscribe_to_fault_reports( void (*callback)(oscc_fault_report_s *report)) { - oscc_result_t ret = OSCC_ERROR; + oscc_result_t result = OSCC_ERROR; + if ( callback != NULL ) { fault_report_callback = callback; - ret = OSCC_OK; + result = OSCC_OK; } - return ret; + + return result; } oscc_result_t oscc_subscribe_to_obd_messages( void (*callback)(struct can_frame *frame)) { - oscc_result_t ret = OSCC_ERROR; + oscc_result_t result = OSCC_ERROR; + if ( callback != NULL ) { obd_frame_callback = callback; - ret = OSCC_OK; + result = OSCC_OK; } - return ret; + + return result; } -static oscc_result_t oscc_enable_brakes( void ) + + + +/* Internal */ +oscc_result_t oscc_enable_brakes( void ) { - oscc_result_t ret = OSCC_ERROR; + oscc_result_t result = OSCC_ERROR; - brake_cmd.enable = 1; - ret = oscc_publish_brake_position( 0 ); + oscc_brake_enable_s brake_enable = + { + .magic[0] = ( uint8_t ) OSCC_MAGIC_BYTE_0, + .magic[1] = ( uint8_t ) OSCC_MAGIC_BYTE_1 + }; + + result = oscc_can_write( + OSCC_BRAKE_ENABLE_CAN_ID, + (void *) &brake_enable, + sizeof(brake_enable) ); - return ret; + + return result; } -static oscc_result_t oscc_enable_throttle( void ) +oscc_result_t oscc_enable_throttle( void ) { - oscc_result_t ret = OSCC_ERROR; + oscc_result_t result = OSCC_ERROR; + - throttle_cmd.enable = 1; + oscc_throttle_enable_s throttle_enable = + { + .magic[0] = ( uint8_t ) OSCC_MAGIC_BYTE_0, + .magic[1] = ( uint8_t ) OSCC_MAGIC_BYTE_1 + }; + + result = oscc_can_write( + OSCC_THROTTLE_ENABLE_CAN_ID, + (void *) &throttle_enable, + sizeof(throttle_enable) ); - ret = oscc_publish_throttle_position( 0 ); - return ret; + return result; } -static oscc_result_t oscc_enable_steering( void ) +oscc_result_t oscc_enable_steering( void ) { - oscc_result_t ret = OSCC_ERROR; + oscc_result_t result = OSCC_ERROR; + + + oscc_steering_enable_s steering_enable = + { + .magic[0] = ( uint8_t ) OSCC_MAGIC_BYTE_0, + .magic[1] = ( uint8_t ) OSCC_MAGIC_BYTE_1 + }; - steering_cmd.enable = 1; + result = oscc_can_write( + OSCC_STEERING_ENABLE_CAN_ID, + (void *) &steering_enable, + sizeof(steering_enable) ); - ret = oscc_publish_steering_torque( 0 ); - return ret; + return result; } -static oscc_result_t oscc_disable_brakes( void ) +oscc_result_t oscc_disable_brakes( void ) { - oscc_result_t ret = OSCC_ERROR; + oscc_result_t result = OSCC_ERROR; - brake_cmd.enable = 0; - ret = oscc_publish_brake_position( 0 ); + oscc_brake_disable_s brake_disable = + { + .magic[0] = ( uint8_t ) OSCC_MAGIC_BYTE_0, + .magic[1] = ( uint8_t ) OSCC_MAGIC_BYTE_1 + }; + + result = oscc_can_write( + OSCC_BRAKE_DISABLE_CAN_ID, + (void *) &brake_disable, + sizeof(brake_disable) ); + - return ret; + return result; } -static oscc_result_t oscc_disable_throttle( void ) +oscc_result_t oscc_disable_throttle( void ) { - oscc_result_t ret = OSCC_ERROR; + oscc_result_t result = OSCC_ERROR; - throttle_cmd.enable = 0; - ret = oscc_publish_throttle_position( 0 ); + oscc_throttle_disable_s throttle_disable = + { + .magic[0] = ( uint8_t ) OSCC_MAGIC_BYTE_0, + .magic[1] = ( uint8_t ) OSCC_MAGIC_BYTE_1 + }; + + result = oscc_can_write( + OSCC_THROTTLE_DISABLE_CAN_ID, + (void *) &throttle_disable, + sizeof(throttle_disable) ); - return ret; + + return result; } -static oscc_result_t oscc_disable_steering( void ) +oscc_result_t oscc_disable_steering( void ) { - oscc_result_t ret = OSCC_ERROR; + oscc_result_t result = OSCC_ERROR; + - steering_cmd.enable = 0; + oscc_steering_disable_s steering_disable = + { + .magic[0] = ( uint8_t ) OSCC_MAGIC_BYTE_0, + .magic[1] = ( uint8_t ) OSCC_MAGIC_BYTE_1 + }; - ret = oscc_publish_steering_torque( 0 ); + result = oscc_can_write( + OSCC_STEERING_DISABLE_CAN_ID, + (void *) &steering_disable, + sizeof(steering_disable) ); - return ret; + + return result; } -static void oscc_update_status( ) +void oscc_update_status( ) { struct can_frame rx_frame; + memset( &rx_frame, 0, sizeof(rx_frame) ); - int result = read( can_socket, &rx_frame, CAN_MTU ); - - while ( result > 0 ) + if ( can_socket != -1 ) { - if ( (rx_frame.data[0] == OSCC_MAGIC_BYTE_0) - && (rx_frame.data[1] = OSCC_MAGIC_BYTE_1) ) + int ret = read( can_socket, &rx_frame, CAN_MTU ); + + while ( ret > 0 ) { - if ( rx_frame.can_id == OSCC_STEERING_REPORT_CAN_ID ) + if ( (rx_frame.data[0] == OSCC_MAGIC_BYTE_0) + && (rx_frame.data[1] == OSCC_MAGIC_BYTE_1) ) { - oscc_steering_report_s *steering_report = - (oscc_steering_report_s *)rx_frame.data; - - if ( steering_report_callback != NULL ) + if ( rx_frame.can_id == OSCC_STEERING_REPORT_CAN_ID ) { - steering_report_callback( steering_report ); - } - } - else if ( rx_frame.can_id == OSCC_THROTTLE_REPORT_CAN_ID ) - { - oscc_throttle_report_s *throttle_report = - ( oscc_throttle_report_s *)rx_frame.data; + oscc_steering_report_s *steering_report = + ( oscc_steering_report_s* ) rx_frame.data; - if ( throttle_report_callback != NULL ) + if ( steering_report_callback != NULL ) + { + steering_report_callback( steering_report ); + } + } + else if ( rx_frame.can_id == OSCC_THROTTLE_REPORT_CAN_ID ) { - throttle_report_callback( throttle_report ); + oscc_throttle_report_s *throttle_report = + ( oscc_throttle_report_s* ) rx_frame.data; + + if ( throttle_report_callback != NULL ) + { + throttle_report_callback( throttle_report ); + } } - } - else if ( rx_frame.can_id == OSCC_BRAKE_REPORT_CAN_ID ) - { - oscc_brake_report_s *brake_report = - ( oscc_brake_report_s *)rx_frame.data; + else if ( rx_frame.can_id == OSCC_BRAKE_REPORT_CAN_ID ) + { + oscc_brake_report_s *brake_report = + ( oscc_brake_report_s* ) rx_frame.data; - if ( brake_report_callback != NULL ) + if ( brake_report_callback != NULL ) + { + brake_report_callback( brake_report ); + } + } + else if ( rx_frame.can_id == OSCC_FAULT_REPORT_CAN_ID ) { - brake_report_callback( brake_report ); + oscc_fault_report_s *fault_report = + ( oscc_fault_report_s* ) rx_frame.data; + + if ( fault_report_callback != NULL ) + { + fault_report_callback( fault_report ); + } } } - else if ( rx_frame.can_id == OSCC_FAULT_REPORT_CAN_ID ) + else { - oscc_fault_report_s *fault_report = - ( oscc_fault_report_s *)rx_frame.data; - - if ( fault_report_callback != NULL ) + if ( obd_frame_callback != NULL ) { - fault_report_callback( fault_report ); + obd_frame_callback( &rx_frame ); } } - } - else - { - if ( obd_frame_callback != NULL ) - { - obd_frame_callback( &rx_frame ); - } - } - result = read( can_socket, &rx_frame, CAN_MTU ); + ret = read( can_socket, &rx_frame, CAN_MTU ); + } } } -static oscc_result_t oscc_can_write( long id, void *msg, unsigned int dlc ) +oscc_result_t oscc_can_write( long id, void *msg, unsigned int dlc ) { - oscc_result_t ret = OSCC_ERROR; + oscc_result_t result = OSCC_ERROR; + - struct can_frame tx_frame; + if ( can_socket != -1 ) + { + struct can_frame tx_frame; - tx_frame.can_id = id; - tx_frame.can_dlc = dlc; - memcpy( tx_frame.data, msg, dlc); + memset( &tx_frame, 0, sizeof(tx_frame) ); + tx_frame.can_id = id; + tx_frame.can_dlc = dlc; + memcpy( tx_frame.data, msg, dlc ); - int result = write( can_socket, &tx_frame, sizeof(tx_frame )); + int ret = write( can_socket, &tx_frame, sizeof(tx_frame) ); - if ( result > 0 ) - { - ret = OSCC_OK; + if ( ret > 0 ) + { + result = OSCC_OK; + } + else + { + printf( "Could not write to socket: %s\n", strerror(errno) ); + } } - return ret; + + return result; } -static oscc_result_t oscc_async_enable( int socket ) +oscc_result_t oscc_async_enable( int socket ) { - oscc_result_t ret = OSCC_ERROR; + oscc_result_t result = OSCC_ERROR; - ret = fcntl( socket, F_SETOWN, getpid( ) ); - if ( ret < 0 ) - { - printf( "set own failed\n" ); - } + int ret = fcntl( socket, F_SETOWN, getpid( ) ); - ret = fcntl( socket, F_SETFL, FASYNC | O_NONBLOCK ); + if ( ret < 0 ) + { + printf( "Setting owner process of socket failed: %s\n", strerror(errno) ); + } + else + { + result = OSCC_OK; + } - if ( ret < 0 ) - { - printf( "set async failed\n" ); - } - return ret; + if ( result == OSCC_OK ) + { + ret = fcntl( socket, F_SETFL, FASYNC | O_NONBLOCK ); + + if ( ret < 0 ) + { + printf( "Setting nonblocking asynchronous socket I/O failed: %s\n", strerror(errno) ); + + result = OSCC_ERROR; + } + } + + + return result; } -static oscc_result_t oscc_init_can( const char *can_channel ) +oscc_result_t oscc_init_can( const char *can_channel ) { - int ret = OSCC_OK; + int result = OSCC_ERROR; + int ret = -1; + struct sigaction sig; + + memset( &sig, 0, sizeof(sig) ); + sigemptyset( &sig.sa_mask ); + sig.sa_flags = SA_RESTART; sig.sa_handler = oscc_update_status; sigaction( SIGIO, &sig, NULL ); - int s = socket( PF_CAN, SOCK_RAW, CAN_RAW ); + int sock = socket( PF_CAN, SOCK_RAW, CAN_RAW ); - if ( s < 0 ) + if ( sock < 0 ) { - printf( "opening can socket failed\n" ); - - ret = OSCC_ERROR; + printf( "Opening CAN socket failed: %s\n", strerror(errno) ); + } + else + { + result = OSCC_OK; } - int status; struct ifreq ifr; + memset( &ifr, 0, sizeof(ifr) ); - if ( ret != OSCC_ERROR ) + if ( result == OSCC_OK ) { strncpy( ifr.ifr_name, can_channel, IFNAMSIZ ); - status = ioctl( s, SIOCGIFINDEX, &ifr ); + ret = ioctl( sock, SIOCGIFINDEX, &ifr ); - if ( status < 0 ) + if ( ret < 0 ) { - printf( "finding can index failed\n" ); + printf( "Finding CAN index failed: %s\n", strerror(errno) ); - ret = OSCC_ERROR; + result = OSCC_ERROR; } } - if ( ret != OSCC_ERROR ) + + if ( result == OSCC_OK ) { struct sockaddr_can can_address; + memset( &can_address, 0, sizeof(can_address) ); can_address.can_family = AF_CAN; can_address.can_ifindex = ifr.ifr_ifindex; - status = bind( s, - (struct sockaddr *)&can_address, - sizeof(can_address)); + ret = bind( + sock, + (struct sockaddr *) &can_address, + sizeof(can_address) ); - if ( status < 0 ) + if ( ret < 0 ) { - printf( "socket binding failed\n" ); + printf( "Socket binding failed: %s\n", strerror(errno) ); - ret = OSCC_ERROR; + result = OSCC_ERROR; } } - if ( ret != OSCC_ERROR ) + + if ( result == OSCC_OK ) { - can_socket = s; + ret = oscc_async_enable( sock ); + + if ( ret != OSCC_OK ) + { + printf( "Enabling asynchronous socket I/O failed\n" ); - ret = OSCC_OK; + result = OSCC_ERROR; + } } - if ( ret != OSCC_ERROR ) + + if ( result == OSCC_OK ) { - status = oscc_async_enable( s ); + /* all prior checks will pass even if a valid interface has not been + set up - attempt to write an empty CAN frame to the interface to see + if it is valid */ + struct can_frame tx_frame; - if ( status != OSCC_OK ) + memset( &tx_frame, 0, sizeof(tx_frame) ); + tx_frame.can_id = 0; + tx_frame.can_dlc = 8; + + int bytes_written = write( sock, &tx_frame, sizeof(tx_frame) ); + + if ( bytes_written < 0 ) { - printf( "async enable failed\n" ); + printf( "Failed to write test frame to %s: %s\n", can_channel, strerror(errno) ); - ret = OSCC_ERROR; + result = OSCC_ERROR; + } + else + { + can_socket = sock; } } - return ret; -} - -static void oscc_init_commands( void ) -{ - brake_cmd.magic[0] = ( uint8_t ) OSCC_MAGIC_BYTE_0; - brake_cmd.magic[1] = ( uint8_t ) OSCC_MAGIC_BYTE_1; - - throttle_cmd.magic[0] = ( uint8_t ) OSCC_MAGIC_BYTE_0; - throttle_cmd.magic[1] = ( uint8_t ) OSCC_MAGIC_BYTE_1; - steering_cmd.magic[0] = ( uint8_t ) OSCC_MAGIC_BYTE_0; - steering_cmd.magic[1] = ( uint8_t ) OSCC_MAGIC_BYTE_1; + return result; } diff --git a/firmware/CMakeLists.txt b/firmware/CMakeLists.txt index 76541787..8c6d6c7b 100644 --- a/firmware/CMakeLists.txt +++ b/firmware/CMakeLists.txt @@ -1,5 +1,3 @@ - - if(TESTS) cmake_minimum_required(VERSION 2.8) @@ -11,9 +9,14 @@ if(TESTS) if(KIA_SOUL) add_definitions(-DKIA_SOUL) + add_subdirectory(brake/kia_soul_petrol/tests) + elseif(KIA_SOUL_EV) + add_definitions(-DKIA_SOUL_EV) + add_subdirectory(brake/kia_soul_ev/tests) + else() + message(FATAL_ERROR "No platform selected - no firmware will be tested") endif() - add_subdirectory(brake/tests) add_subdirectory(can_gateway/tests) add_subdirectory(steering/tests) add_subdirectory(throttle/tests) @@ -55,8 +58,10 @@ else() set(CMAKE_CXX_FLAGS "-std=gnu++11 -Os") option(DEBUG "Enable debug mode" OFF) - option(KIA_SOUL "Build firmware for Kia Soul" OFF) + option(KIA_SOUL "Build firmware for the petrol Kia Soul" OFF) + option(KIA_SOUL_EV "Build firmware for the Kia Soul EV" OFF) option(BRAKE_STARTUP_TEST "Enable brake startup sensor tests" ON) + option(STEERING_OVERRIDE "Enable steering override" ON) set(SERIAL_PORT_BRAKE "/dev/ttyACM0" CACHE STRING "Serial port of the brake module") set(SERIAL_BAUD_BRAKE "115200" CACHE STRING "Serial baud rate of the brake module") @@ -76,16 +81,23 @@ else() if(KIA_SOUL) add_definitions(-DKIA_SOUL) + elseif(KIA_SOUL_EV) + add_definitions(-DKIA_SOUL_EV) else() - message(WARNING "No platform selected - no firmware will be built") + message(FATAL_ERROR "No platform selected - no firmware will be built") endif() - if(BRAKE_STARTUP_TEST) + if(KIA_SOUL AND BRAKE_STARTUP_TEST) add_definitions(-DBRAKE_STARTUP_TEST) - else() + elseif(KIA_SOUL AND NOT BRAKE_STARTUP_TEST) message(WARNING "Brake sensor startup tests disabled") endif() + if(STEERING_OVERRIDE) + add_definitions(-DSTEERING_OVERRIDE) + message(WARNING "Steering override is enabled. This is an experimental feature! Attempting to grab the steering wheel while the system is active could result in serious injury. The preferred method of operator override for steering is to utilize the brake pedal or E-stop button.") + endif() + add_subdirectory(brake) add_subdirectory(can_gateway) add_subdirectory(steering) diff --git a/firmware/brake/CMakeLists.txt b/firmware/brake/CMakeLists.txt index 0dfa03a4..f01a1ddd 100644 --- a/firmware/brake/CMakeLists.txt +++ b/firmware/brake/CMakeLists.txt @@ -1,6 +1,5 @@ project(brake) -set(ARDUINO_DEFAULT_BOARD mega2560) SET(ARDUINO_DEFAULT_PORT ${SERIAL_PORT_BRAKE}) set(ARDUINO_DEFAULT_BAUDRATE ${SERIAL_BAUD_BRAKE}) @@ -14,36 +13,8 @@ add_custom_target( brake-monitor-log COMMAND screen -L ${ARDUINO_DEFAULT_PORT} ${ARDUINO_DEFAULT_BAUDRATE}) -generate_arduino_firmware( - brake - SRCS - ${CMAKE_SOURCE_DIR}/common/libs/arduino_init/arduino_init.cpp - ${CMAKE_SOURCE_DIR}/common/libs/mcp_can/mcp_can.cpp - ${CMAKE_SOURCE_DIR}/common/libs/pid/oscc_pid.cpp - ${CMAKE_SOURCE_DIR}/common/libs/serial/oscc_serial.cpp - ${CMAKE_SOURCE_DIR}/common/libs/can/oscc_can.cpp - ${CMAKE_SOURCE_DIR}/common/libs/timer/oscc_timer.cpp - src/main.cpp - src/globals.cpp - src/accumulator.cpp - src/helper.cpp - src/master_cylinder.cpp - src/brake_control.cpp - src/communications.cpp - src/init.cpp - src/timers.cpp) - -target_include_directories( - brake - PRIVATE - include - ${CMAKE_SOURCE_DIR}/common/include - ${CMAKE_SOURCE_DIR}/common/libs/arduino_init - ${CMAKE_SOURCE_DIR}/common/libs/mcp_can - ${CMAKE_SOURCE_DIR}/common/libs/pid - ${CMAKE_SOURCE_DIR}/common/libs/serial - ${CMAKE_SOURCE_DIR}/common/libs/can - ${CMAKE_SOURCE_DIR}/common/libs/timer - ${CMAKE_SOURCE_DIR}/../api/include) - -add_subdirectory(utils) +if(KIA_SOUL) + add_subdirectory(kia_soul_petrol) +elseif(KIA_SOUL_EV) + add_subdirectory(kia_soul_ev) +endif() diff --git a/firmware/brake/kia_soul_ev/CMakeLists.txt b/firmware/brake/kia_soul_ev/CMakeLists.txt new file mode 100644 index 00000000..ee6cdaa7 --- /dev/null +++ b/firmware/brake/kia_soul_ev/CMakeLists.txt @@ -0,0 +1,32 @@ +set(ARDUINO_DEFAULT_BOARD uno) + +generate_arduino_firmware( + brake + SRCS + ${CMAKE_SOURCE_DIR}/common/libs/arduino_init/arduino_init.cpp + ${CMAKE_SOURCE_DIR}/common/libs/DAC_MCP49xx/DAC_MCP49xx.cpp + ${CMAKE_SOURCE_DIR}/common/libs/mcp_can/mcp_can.cpp + ${CMAKE_SOURCE_DIR}/common/libs/serial/oscc_serial.cpp + ${CMAKE_SOURCE_DIR}/common/libs/can/oscc_can.cpp + ${CMAKE_SOURCE_DIR}/common/libs/dac/oscc_dac.cpp + ${CMAKE_SOURCE_DIR}/common/libs/timer/oscc_timer.cpp + src/main.cpp + src/globals.cpp + src/brake_control.cpp + src/communications.cpp + src/init.cpp + src/timers.cpp) + +target_include_directories( + brake + PRIVATE + include + ${CMAKE_SOURCE_DIR}/common/include + ${CMAKE_SOURCE_DIR}/common/libs/arduino_init + ${CMAKE_SOURCE_DIR}/common/libs/DAC_MCP49xx + ${CMAKE_SOURCE_DIR}/common/libs/mcp_can + ${CMAKE_SOURCE_DIR}/common/libs/serial + ${CMAKE_SOURCE_DIR}/common/libs/can + ${CMAKE_SOURCE_DIR}/common/libs/dac + ${CMAKE_SOURCE_DIR}/common/libs/timer + ${CMAKE_SOURCE_DIR}/../api/include) diff --git a/firmware/brake/kia_soul_ev/include/brake_control.h b/firmware/brake/kia_soul_ev/include/brake_control.h new file mode 100644 index 00000000..fa7468af --- /dev/null +++ b/firmware/brake/kia_soul_ev/include/brake_control.h @@ -0,0 +1,115 @@ +/** + * @file brake_control.h + * @brief Control of the brake system. + * + */ + + +#ifndef _OSCC_BRAKE_CONTROL_H_ +#define _OSCC_BRAKE_CONTROL_H_ + + +#include + + +/** + * @brief Brake pedal position values. + * + * Contains high and low brake pedal values. + * + */ +typedef struct +{ + uint16_t low; /* Low value of brake pedal position. */ + + uint16_t high; /* High value of brake pedal position. */ +} brake_pedal_position_s; + + +/** + * @brief Current brake control state. + * + * Current state of the brake module control system. + * + */ +typedef struct +{ + bool enabled; /* Flag indicating whether control is currently enabled. */ + + bool operator_override; /* Flag indicating whether brake pedal was manually + pressed by operator. */ + + uint8_t dtcs; /* Bitfield of faults present in the module. */ +} brake_control_state_s; + + +// **************************************************************************** +// Function: check_for_operator_override +// +// Purpose: Checks to see if the vehicle's operator has manually pressed +// the brake pedal and disables control if they have. +// +// Returns: void +// +// Parameters: void +// +// **************************************************************************** +void check_for_operator_override( void ); + + +// **************************************************************************** +// Function: check_for_sensor_faults +// +// Purpose: Checks to see if valid values are being read from the sensors. +// +// Returns: void +// +// Parameters: void +// +// **************************************************************************** +void check_for_sensor_faults( void ); + + +// **************************************************************************** +// Function: update_brake +// +// Purpose: Writes brake spoof values to DAC. +// +// Returns: void +// +// Parameters: spoof_command_high - high value of spoof command +// spoof_command_low - low value of spoof command +// +// **************************************************************************** +void update_brake( + uint16_t spoof_command_high, + uint16_t spoof_command_low ); + + +// **************************************************************************** +// Function: enable_control +// +// Purpose: Enable control of the brake system. +// +// Returns: void +// +// Parameters: void +// +// **************************************************************************** +void enable_control( void ); + + +// **************************************************************************** +// Function: disable_control +// +// Purpose: Disable control of the brake system. +// +// Returns: void +// +// Parameters: void +// +// **************************************************************************** +void disable_control( void ); + + +#endif /* _OSCC_BRAKE_CONTROL_H_ */ diff --git a/firmware/brake/include/communications.h b/firmware/brake/kia_soul_ev/include/communications.h similarity index 91% rename from firmware/brake/include/communications.h rename to firmware/brake/kia_soul_ev/include/communications.h index 8f9a6236..f672488c 100644 --- a/firmware/brake/include/communications.h +++ b/firmware/brake/kia_soul_ev/include/communications.h @@ -5,8 +5,8 @@ */ -#ifndef _OSCC_KIA_SOUL_BRAKE_COMMUNICATIONS_H_ -#define _OSCC_KIA_SOUL_BRAKE_COMMUNICATIONS_H_ +#ifndef _OSCC_BRAKE_COMMUNICATIONS_H_ +#define _OSCC_BRAKE_COMMUNICATIONS_H_ // **************************************************************************** @@ -48,6 +48,7 @@ void publish_fault_report( void ); // **************************************************************************** void check_for_controller_command_timeout( void ); + // **************************************************************************** // Function: check_for_incoming_message // @@ -61,4 +62,4 @@ void check_for_controller_command_timeout( void ); void check_for_incoming_message( void ); -#endif /* _OSCC_KIA_SOUL_BRAKE_COMMUNICATIONS_H_ */ +#endif /* _OSCC_BRAKE_COMMUNICATIONS_H_ */ diff --git a/firmware/brake/kia_soul_ev/include/globals.h b/firmware/brake/kia_soul_ev/include/globals.h new file mode 100644 index 00000000..3b863e62 --- /dev/null +++ b/firmware/brake/kia_soul_ev/include/globals.h @@ -0,0 +1,84 @@ +/** + * @file globals.h + * @brief Module globals. + * + */ + + +#ifndef _OSCC_BRAKE_GLOBALS_H_ +#define _OSCC_BRAKE_GLOBALS_H_ + + +#include "brake_control.h" +#include "DAC_MCP49xx.h" +#include "mcp_can.h" + + +/* + * @brief Chip select pin of the DAC IC. + * + */ +#define PIN_DAC_CHIP_SELECT ( 9 ) + +/* + * @brief Chip select pin of the CAN IC. + * + */ +#define PIN_CAN_CHIP_SELECT ( 10 ) + +/* + * @brief High signal pin of the brake pedal position sensor. + * + */ +#define PIN_BRAKE_PEDAL_POSITION_SENSOR_HIGH ( A0 ) + +/* + * @brief Low signal pin of the brake pedal position sensor. + * + */ +#define PIN_BRAKE_PEDAL_POSITION_SENSOR_LOW ( A1 ) + +/* + * @brief High signal pin of the brake pedal position spoof output. + * + */ +#define PIN_BRAKE_PEDAL_POSITION_SPOOF_HIGH ( A2 ) + +/* + * @brief Low signal pin of the brake pedal position spoof output. + * + */ +#define PIN_BRAKE_PEDAL_POSITION_SPOOF_LOW ( A3 ) + +/* + * @brief Relay enable pin for the spoof output. + * + */ +#define PIN_SPOOF_ENABLE ( 6 ) + +/* + * @brief Relay enable pin for the brake lights. + * + */ +#define PIN_BRAKE_LIGHT_ENABLE ( 5 ) + + +#ifdef GLOBAL_DEFINED + DAC_MCP49xx g_dac( DAC_MCP49xx::MCP4922, PIN_DAC_CHIP_SELECT ); + MCP_CAN g_control_can( PIN_CAN_CHIP_SELECT ); + + #define EXTERN +#else + extern DAC_MCP49xx g_dac; + extern MCP_CAN g_control_can; + + #define EXTERN extern +#endif + + +EXTERN volatile bool g_brake_command_timeout; + +EXTERN volatile brake_control_state_s g_brake_control_state; + + +#endif /* _OSCC_BRAKE_GLOBALS_H_ */ diff --git a/firmware/brake/include/init.h b/firmware/brake/kia_soul_ev/include/init.h similarity index 90% rename from firmware/brake/include/init.h rename to firmware/brake/kia_soul_ev/include/init.h index cd6cbe40..df8f22d1 100644 --- a/firmware/brake/include/init.h +++ b/firmware/brake/kia_soul_ev/include/init.h @@ -5,8 +5,8 @@ */ -#ifndef _OSCC_KIA_SOUL_BRAKE_INIT_H_ -#define _OSCC_KIA_SOUL_BRAKE_INIT_H_ +#ifndef _OSCC_BRAKE_INIT_H_ +#define _OSCC_BRAKE_INIT_H_ // **************************************************************************** @@ -48,4 +48,4 @@ void init_devices( void ); void init_communication_interfaces( void ); -#endif /* _OSCC_KIA_SOUL_BRAKE_INIT_H_ */ +#endif /* _OSCC_BRAKE_INIT_H_ */ diff --git a/firmware/brake/include/timers.h b/firmware/brake/kia_soul_ev/include/timers.h similarity index 76% rename from firmware/brake/include/timers.h rename to firmware/brake/kia_soul_ev/include/timers.h index 70f6ab0d..7ce05c90 100644 --- a/firmware/brake/include/timers.h +++ b/firmware/brake/kia_soul_ev/include/timers.h @@ -5,8 +5,8 @@ */ -#ifndef _OSCC_KIA_SOUL_BRAKE_TIMERS_H_ -#define _OSCC_KIA_SOUL_BRAKE_TIMERS_H_ +#ifndef _OSCC_BRAKE_TIMERS_H_ +#define _OSCC_BRAKE_TIMERS_H_ // **************************************************************************** @@ -22,4 +22,4 @@ void start_timers( void ); -#endif /* _OSCC_KIA_SOUL_BRAKE_TIMERS_H_ */ +#endif /* _OSCC_BRAKE_TIMERS_H_ */ diff --git a/firmware/brake/kia_soul_ev/src/brake_control.cpp b/firmware/brake/kia_soul_ev/src/brake_control.cpp new file mode 100644 index 00000000..0ea61035 --- /dev/null +++ b/firmware/brake/kia_soul_ev/src/brake_control.cpp @@ -0,0 +1,206 @@ +/** + * @file brake_control.cpp + * + */ + + +#include +#include + +#include "can_protocols/brake_can_protocol.h" +#include "brake_control.h" +#include "communications.h" +#include "debug.h" +#include "dtc.h" +#include "globals.h" +#include "oscc_dac.h" +#include "vehicles.h" + + +/* + * @brief Number of consecutive faults that can occur when reading the + * sensors before control is disabled. + * + */ +#define SENSOR_VALIDITY_CHECK_FAULT_COUNT ( 4 ) + + +static void read_brake_pedal_position_sensor( + brake_pedal_position_s * const value ); + + +void check_for_operator_override( void ) +{ + if ( g_brake_control_state.enabled == true + || g_brake_control_state.operator_override == true ) + { + brake_pedal_position_s brake_pedal_position; + + read_brake_pedal_position_sensor( &brake_pedal_position ); + + uint32_t brake_pedal_position_average = + (brake_pedal_position.low + brake_pedal_position.high) / 2; + + if ( brake_pedal_position_average >= BRAKE_PEDAL_OVERRIDE_THRESHOLD ) + { + disable_control( ); + + DTC_SET( + g_brake_control_state.dtcs, + OSCC_BRAKE_DTC_OPERATOR_OVERRIDE ); + + publish_fault_report( ); + + g_brake_control_state.operator_override = true; + + DEBUG_PRINTLN( "Operator override" ); + } + else + { + DTC_CLEAR( + g_brake_control_state.dtcs, + OSCC_BRAKE_DTC_OPERATOR_OVERRIDE ); + + g_brake_control_state.operator_override = false; + } + } +} + + +void check_for_sensor_faults( void ) +{ + if ( (g_brake_control_state.enabled == true) + || DTC_CHECK(g_brake_control_state.dtcs, OSCC_BRAKE_DTC_INVALID_SENSOR_VAL) ) + { + static int fault_count = 0; + + brake_pedal_position_s brake_pedal_position; + + read_brake_pedal_position_sensor( &brake_pedal_position ); + + // sensor pins tied to ground - a value of zero indicates disconnection + if( (brake_pedal_position.high == 0) + || (brake_pedal_position.low == 0) ) + { + ++fault_count; + + if( fault_count >= SENSOR_VALIDITY_CHECK_FAULT_COUNT ) + { + disable_control( ); + + DTC_SET( + g_brake_control_state.dtcs, + OSCC_BRAKE_DTC_INVALID_SENSOR_VAL ); + + publish_fault_report( ); + + DEBUG_PRINTLN( "Bad value read from brake pedal position sensor" ); + } + } + else + { + DTC_CLEAR( + g_brake_control_state.dtcs, + OSCC_BRAKE_DTC_INVALID_SENSOR_VAL ); + + fault_count = 0; + } + } +} + + +void update_brake( + uint16_t spoof_command_high, + uint16_t spoof_command_low ) +{ + if ( g_brake_control_state.enabled == true ) + { + uint16_t spoof_high = + constrain( + spoof_command_high, + BRAKE_SPOOF_HIGH_SIGNAL_RANGE_MIN, + BRAKE_SPOOF_HIGH_SIGNAL_RANGE_MAX ); + + uint16_t spoof_low = + constrain( + spoof_command_low, + BRAKE_SPOOF_LOW_SIGNAL_RANGE_MIN, + BRAKE_SPOOF_LOW_SIGNAL_RANGE_MAX ); + + if( (spoof_high > BRAKE_LIGHT_SPOOF_HIGH_THRESHOLD) + || (spoof_low > BRAKE_LIGHT_SPOOF_LOW_THRESHOLD) ) + { + cli(); + digitalWrite(PIN_BRAKE_LIGHT_ENABLE, HIGH); + sei(); + } + else + { + cli(); + digitalWrite(PIN_BRAKE_LIGHT_ENABLE, LOW); + sei(); + } + + cli(); + g_dac.outputA( spoof_high ); + g_dac.outputB( spoof_low ); + sei(); + } +} + + +void enable_control( void ) +{ + if( g_brake_control_state.enabled == false + && g_brake_control_state.operator_override == false ) + { + const uint16_t num_samples = 20; + prevent_signal_discontinuity( + g_dac, + num_samples, + PIN_BRAKE_PEDAL_POSITION_SENSOR_HIGH, + PIN_BRAKE_PEDAL_POSITION_SENSOR_LOW ); + + cli(); + digitalWrite( PIN_SPOOF_ENABLE, HIGH ); + sei(); + + g_brake_command_timeout = false; + g_brake_control_state.enabled = true; + + DEBUG_PRINTLN( "Control enabled" ); + } +} + + +void disable_control( void ) +{ + if( g_brake_control_state.enabled == true ) + { + const uint16_t num_samples = 20; + prevent_signal_discontinuity( + g_dac, + num_samples, + PIN_BRAKE_PEDAL_POSITION_SENSOR_HIGH, + PIN_BRAKE_PEDAL_POSITION_SENSOR_LOW ); + + cli(); + digitalWrite( PIN_SPOOF_ENABLE, LOW ); + sei(); + + g_brake_command_timeout = false; + g_brake_control_state.enabled = false; + + DEBUG_PRINTLN( "Control disabled" ); + } +} + + +static void read_brake_pedal_position_sensor( + brake_pedal_position_s * const value ) +{ + cli(); + value->high = analogRead( PIN_BRAKE_PEDAL_POSITION_SENSOR_HIGH ); + value->low = analogRead( PIN_BRAKE_PEDAL_POSITION_SENSOR_LOW ); + sei(); +} diff --git a/firmware/brake/kia_soul_ev/src/communications.cpp b/firmware/brake/kia_soul_ev/src/communications.cpp new file mode 100644 index 00000000..bcaf61ea --- /dev/null +++ b/firmware/brake/kia_soul_ev/src/communications.cpp @@ -0,0 +1,157 @@ +/** + * @file communications.cpp + * + */ + + +#include + +#include "can_protocols/brake_can_protocol.h" +#include "can_protocols/fault_can_protocol.h" +#include "brake_control.h" +#include "communications.h" +#include "debug.h" +#include "globals.h" +#include "mcp_can.h" +#include "oscc_can.h" + + +static void process_rx_frame( + const can_frame_s * const frame ); + +static void process_brake_command( + const uint8_t * const data ); + +static void process_fault_report( + const uint8_t * const data ); + + +void publish_brake_report( void ) +{ + oscc_brake_report_s brake_report; + + brake_report.magic[0] = (uint8_t) OSCC_MAGIC_BYTE_0; + brake_report.magic[1] = (uint8_t) OSCC_MAGIC_BYTE_1; + brake_report.enabled = (uint8_t) g_brake_control_state.enabled; + brake_report.operator_override = (uint8_t) g_brake_control_state.operator_override; + brake_report.dtcs = g_brake_control_state.dtcs; + + cli(); + g_control_can.sendMsgBuf( + OSCC_BRAKE_REPORT_CAN_ID, + CAN_STANDARD, + OSCC_BRAKE_REPORT_CAN_DLC, + (uint8_t*) &brake_report ); + sei(); +} + + +void publish_fault_report( void ) +{ + oscc_fault_report_s fault_report; + + fault_report.magic[0] = (uint8_t) OSCC_MAGIC_BYTE_0; + fault_report.magic[1] = (uint8_t) OSCC_MAGIC_BYTE_1; + fault_report.fault_origin_id = FAULT_ORIGIN_BRAKE; + fault_report.dtcs = g_brake_control_state.dtcs; + + cli(); + g_control_can.sendMsgBuf( + OSCC_FAULT_REPORT_CAN_ID, + CAN_STANDARD, + OSCC_FAULT_REPORT_CAN_DLC, + (uint8_t *) &fault_report ); + sei(); +} + + +void check_for_controller_command_timeout( void ) +{ + if( g_brake_control_state.enabled == true ) + { + if( g_brake_command_timeout == true ) + { + disable_control( ); + + publish_fault_report( ); + + DEBUG_PRINTLN( "Timeout waiting for controller command" ); + } + } +} + + +void check_for_incoming_message( void ) +{ + can_frame_s rx_frame; + can_status_t ret = check_for_rx_frame( g_control_can, &rx_frame ); + + if( ret == CAN_RX_FRAME_AVAILABLE ) + { + process_rx_frame( &rx_frame ); + } +} + + +static void process_rx_frame( + const can_frame_s * const frame ) +{ + if ( frame != NULL ) + { + if( (frame->data[0] == OSCC_MAGIC_BYTE_0) + && (frame->data[1] == OSCC_MAGIC_BYTE_1) ) + { + if ( frame->id == OSCC_BRAKE_ENABLE_CAN_ID ) + { + enable_control( ); + } + else if ( frame->id == OSCC_BRAKE_DISABLE_CAN_ID ) + { + disable_control( ); + } + else if ( frame->id == OSCC_BRAKE_COMMAND_CAN_ID ) + { + process_brake_command( frame->data ); + } + else if ( frame->id == OSCC_FAULT_REPORT_CAN_ID ) + { + process_fault_report( frame->data ); + } + } + } +} + + +static void process_brake_command( + const uint8_t * const data ) +{ + if ( data != NULL ) + { + const oscc_brake_command_s * const brake_command = + (oscc_brake_command_s *) data; + + update_brake( + brake_command->spoof_value_high, + brake_command->spoof_value_low ); + + g_brake_command_timeout = false; + } +} + + +static void process_fault_report( + const uint8_t * const data ) +{ + if ( data != NULL ) + { + const oscc_fault_report_s * const fault_report = + (oscc_fault_report_s *) data; + + disable_control( ); + + DEBUG_PRINT( "Fault report received from: " ); + DEBUG_PRINT( fault_report->fault_origin_id ); + DEBUG_PRINT( " DTCs: "); + DEBUG_PRINTLN( fault_report->dtcs ); + } +} diff --git a/firmware/brake/kia_soul_ev/src/globals.cpp b/firmware/brake/kia_soul_ev/src/globals.cpp new file mode 100644 index 00000000..8b6333ad --- /dev/null +++ b/firmware/brake/kia_soul_ev/src/globals.cpp @@ -0,0 +1,9 @@ +/** + * @file globals.cpp + * + */ + + +#define GLOBAL_DEFINED + +#include "globals.h" diff --git a/firmware/brake/kia_soul_ev/src/init.cpp b/firmware/brake/kia_soul_ev/src/init.cpp new file mode 100644 index 00000000..39a0401e --- /dev/null +++ b/firmware/brake/kia_soul_ev/src/init.cpp @@ -0,0 +1,54 @@ +/** + * @file init.cpp + * + */ + + +#include + +#include "can_protocols/brake_can_protocol.h" +#include "communications.h" +#include "debug.h" +#include "globals.h" +#include "init.h" +#include "oscc_can.h" +#include "oscc_serial.h" + + +void init_globals( void ) +{ + g_brake_control_state.enabled = false; + g_brake_control_state.operator_override = false; + g_brake_control_state.dtcs = 0; + + g_brake_command_timeout = false; +} + + +void init_devices( void ) +{ + pinMode( PIN_DAC_CHIP_SELECT, OUTPUT ); + pinMode( PIN_BRAKE_PEDAL_POSITION_SENSOR_HIGH, INPUT ); + pinMode( PIN_BRAKE_PEDAL_POSITION_SENSOR_LOW, INPUT ); + pinMode( PIN_BRAKE_PEDAL_POSITION_SPOOF_HIGH, INPUT ); + pinMode( PIN_BRAKE_PEDAL_POSITION_SPOOF_LOW, INPUT ); + pinMode( PIN_SPOOF_ENABLE, OUTPUT ); + pinMode( PIN_BRAKE_LIGHT_ENABLE, OUTPUT ); + + cli(); + digitalWrite( PIN_DAC_CHIP_SELECT, HIGH ); + digitalWrite( PIN_SPOOF_ENABLE, LOW ); + digitalWrite( PIN_BRAKE_LIGHT_ENABLE, LOW ); + sei(); +} + + +void init_communication_interfaces( void ) +{ + #ifdef DEBUG + init_serial( ); + #endif + + DEBUG_PRINT( "init Control CAN - " ); + init_can( g_control_can ); +} diff --git a/firmware/brake/kia_soul_ev/src/main.cpp b/firmware/brake/kia_soul_ev/src/main.cpp new file mode 100644 index 00000000..7b800405 --- /dev/null +++ b/firmware/brake/kia_soul_ev/src/main.cpp @@ -0,0 +1,35 @@ +/** + * @file main.cpp + * + */ + + +#include "arduino_init.h" +#include "brake_control.h" +#include "communications.h" +#include "debug.h" +#include "init.h" +#include "timers.h" + + +int main( void ) +{ + init_arduino( ); + + init_globals( ); + + init_devices( ); + + init_communication_interfaces( ); + + start_timers( ); + + DEBUG_PRINTLN( "init complete" ); + + while( true ) + { + check_for_incoming_message( ); + + check_for_operator_override( ); + } +} diff --git a/firmware/brake/kia_soul_ev/src/timers.cpp b/firmware/brake/kia_soul_ev/src/timers.cpp new file mode 100644 index 00000000..3179348e --- /dev/null +++ b/firmware/brake/kia_soul_ev/src/timers.cpp @@ -0,0 +1,45 @@ +/** + * @file timers.cpp + * + */ + + +#include + +#include "brake_control.h" +#include "can_protocols/brake_can_protocol.h" +#include "communications.h" +#include "globals.h" +#include "oscc_timer.h" +#include "timers.h" + + +/* + * @brief Fault checking frequency. [Hz] + * + */ +#define FAULT_CHECK_FREQUENCY_IN_HZ ( 5 ) + + +static void check_for_faults( void ); + + +void start_timers( void ) +{ + timer1_init( FAULT_CHECK_FREQUENCY_IN_HZ, check_for_faults ); + timer2_init( OSCC_BRAKE_REPORT_PUBLISH_FREQ_IN_HZ, publish_brake_report ); +} + + +static void check_for_faults( void ) +{ + cli(); + + check_for_controller_command_timeout( ); + + check_for_sensor_faults( ); + + g_brake_command_timeout = true; + + sei(); +} diff --git a/firmware/brake/kia_soul_ev/tests/CMakeLists.txt b/firmware/brake/kia_soul_ev/tests/CMakeLists.txt new file mode 100644 index 00000000..900e260e --- /dev/null +++ b/firmware/brake/kia_soul_ev/tests/CMakeLists.txt @@ -0,0 +1,60 @@ +project(brake-unit-tests) + +add_library( + brake + SHARED + ../src/communications.cpp + ../src/globals.cpp + ../src/brake_control.cpp + ${CMAKE_SOURCE_DIR}/common/libs/can/oscc_can.cpp + ${CMAKE_SOURCE_DIR}/common/libs/dac/oscc_dac.cpp + ${CMAKE_SOURCE_DIR}/common/testing/mocks/ + ${CMAKE_SOURCE_DIR}/common/testing/mocks/Arduino_mock.cpp + ${CMAKE_SOURCE_DIR}/common/testing/mocks/mcp_can_mock.cpp + ${CMAKE_SOURCE_DIR}/common/testing/mocks/DAC_MCP49xx_mock.cpp) + +target_include_directories( + brake + PRIVATE + ../include + ${CMAKE_SOURCE_DIR}/common/include + ${CMAKE_SOURCE_DIR}/common/libs/can + ${CMAKE_SOURCE_DIR}/common/libs/dac + ${CMAKE_SOURCE_DIR}/common/libs/signal_smoothing + ${CMAKE_SOURCE_DIR}/common/testing/mocks + ${CMAKE_SOURCE_DIR}/../api/include) + +add_executable( + brake-unit-test + features/step_definitions/test.cpp) + +target_link_libraries( + brake-unit-test + PRIVATE + brake + ${CMAKE_SOURCE_DIR}/common/testing/framework/cucumber-cpp/lib/libcucumber-cpp.a + ${CMAKE_SOURCE_DIR}/common/testing/framework/cgreen/lib/libcgreen.so) + +target_include_directories( + brake-unit-test + PRIVATE + ../include + ${CMAKE_SOURCE_DIR}/common/include + ${CMAKE_SOURCE_DIR}/common/libs/can + ${CMAKE_SOURCE_DIR}/common/testing/mocks + ${CMAKE_SOURCE_DIR}/common/testing/framework/cucumber-cpp/include + ${CMAKE_SOURCE_DIR}/common/testing/framework/cgreen/include + ${CMAKE_SOURCE_DIR}/../api/include) + +add_custom_target( + run-brake-unit-tests + DEPENDS + brake-unit-test + COMMAND + brake-unit-test --port=3902 >/dev/null & cucumber _2.0.0_ ${CMAKE_CURRENT_SOURCE_DIR}/features ) + +add_custom_target( + run-brake-property-tests + COMMAND + cargo test -- --test-threads=1 + WORKING_DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR}/property) diff --git a/firmware/brake/kia_soul_ev/tests/features/checking_faults.feature b/firmware/brake/kia_soul_ev/tests/features/checking_faults.feature new file mode 100644 index 00000000..adc6533c --- /dev/null +++ b/firmware/brake/kia_soul_ev/tests/features/checking_faults.feature @@ -0,0 +1,46 @@ +# language: en + +Feature: Checking for faults + + If the module encounters a fault condition, it should disable control and + publish a fault report. + + Scenario: A sensor becomes temporarily disconnected + Given brake control is enabled + + When a sensor becomes temporarily disconnected + + Then control should remain enabled + + + Scenario: A sensor becomes permanently disconnected + Given brake control is enabled + + When a sensor becomes permanently disconnected + + Then control should be disabled + And a fault report should be published + + + Scenario: Controller command timeout + Given brake control is enabled + + When the time since the last received controller command exceeds the timeout + + Then control should be disabled + And a fault report should be published + + + Scenario Outline: Operator override + Given brake control is enabled + + When the operator applies to the accelerator + + Then control should be disabled + And a fault report should be published + + Examples: + | sensor_val | + | 250 | + | 500 | + | 1000 | diff --git a/firmware/brake/kia_soul_ev/tests/features/receiving_messages.feature b/firmware/brake/kia_soul_ev/tests/features/receiving_messages.feature new file mode 100644 index 00000000..a9c130a9 --- /dev/null +++ b/firmware/brake/kia_soul_ev/tests/features/receiving_messages.feature @@ -0,0 +1,63 @@ +# language: en + +Feature: Receiving commands + + Commands received from a application should be processed and acted upon. + + + Scenario: Enable brake command sent from application + Given brake control is disabled + + When an enable brake command is received + + Then control should be enabled + + + Scenario: Disable brake command sent from application + Given brake control is enabled + + When a disable brake command is received + + Then control should be disabled + + + Scenario: Fault report sent from a different module + Given brake control is enabled + + When a fault report is received + + Then control should be disabled + + + Scenario Outline: Spoof value sent from application + Given brake control is enabled + + When a command is received with spoof values and + + Then should be sent to DAC A + And should be sent to DAC B + + Examples: + | high | low | + | 2300 | 250 | + | 2000 | 300 | + | 1500 | 500 | + | 1000 | 750 | + | 750 | 1000 | + | 550 | 1100 | + + + Scenario Outline: Spoof value sent from application outside valid range + Given brake control is enabled + + When a command is received with spoof values and + + Then should be sent to DAC A + And should be sent to DAC B + + Examples: + | high | low | high_clamped | low_clamped | + | 4000 | 0 | 2351 | 249 | + | 3500 | 500 | 2351 | 500 | + | 500 | 3500 | 521 | 1146 | + | 0 | 4000 | 521 | 1146 | diff --git a/firmware/brake/kia_soul_ev/tests/features/sending_reports.feature b/firmware/brake/kia_soul_ev/tests/features/sending_reports.feature new file mode 100644 index 00000000..8edd780f --- /dev/null +++ b/firmware/brake/kia_soul_ev/tests/features/sending_reports.feature @@ -0,0 +1,12 @@ +# language: en + +Feature: Sending reports + + Brake reports should be published to the control CAN bus. + + + Scenario: Brake report published + When a brake report is published + + Then a brake report should be put on the control CAN bus + And the brake report's fields should be set diff --git a/firmware/brake/kia_soul_ev/tests/features/step_definitions/checking_faults.cpp b/firmware/brake/kia_soul_ev/tests/features/step_definitions/checking_faults.cpp new file mode 100644 index 00000000..b9bb0a51 --- /dev/null +++ b/firmware/brake/kia_soul_ev/tests/features/step_definitions/checking_faults.cpp @@ -0,0 +1,74 @@ +WHEN("^a sensor becomes temporarily disconnected$") +{ + g_mock_arduino_analog_read_return[0] = 0; + + check_for_sensor_faults(); + + check_for_sensor_faults(); + + check_for_sensor_faults(); +} + + +WHEN("^a sensor becomes permanently disconnected$") +{ + g_mock_arduino_analog_read_return[0] = 0; + g_mock_arduino_analog_read_return[1] = 0; + + // must call function enough times to exceed the fault limit + for( int i = 0; i < 100; ++i ) + { + check_for_sensor_faults(); + } +} + + +WHEN("^the time since the last received controller command exceeds the timeout$") +{ + g_brake_command_timeout = true; + + check_for_controller_command_timeout(); +} + + +WHEN("^the operator applies (.*) to the accelerator$") +{ + REGEX_PARAM(int, brake_sensor_val); + + g_mock_arduino_analog_read_return[0] = brake_sensor_val; + g_mock_arduino_analog_read_return[1] = brake_sensor_val; + + + check_for_operator_override(); +} + + +THEN("^control should remain enabled") +{ + assert_that( + g_brake_control_state.enabled, + is_equal_to(1)); +} + + +THEN("^a fault report should be published$") +{ + assert_that(g_mock_mcp_can_send_msg_buf_id, is_equal_to(OSCC_FAULT_REPORT_CAN_ID)); + assert_that(g_mock_mcp_can_send_msg_buf_ext, is_equal_to(CAN_STANDARD)); + assert_that(g_mock_mcp_can_send_msg_buf_len, is_equal_to(OSCC_FAULT_REPORT_CAN_DLC)); + + oscc_fault_report_s * fault_report = + (oscc_fault_report_s *) g_mock_mcp_can_send_msg_buf_buf; + + assert_that( + fault_report->magic[0], + is_equal_to(OSCC_MAGIC_BYTE_0)); + + assert_that( + fault_report->magic[1], + is_equal_to(OSCC_MAGIC_BYTE_1)); + + assert_that( + fault_report->fault_origin_id, + is_equal_to(FAULT_ORIGIN_BRAKE)); +} diff --git a/firmware/brake/kia_soul_ev/tests/features/step_definitions/common.cpp b/firmware/brake/kia_soul_ev/tests/features/step_definitions/common.cpp new file mode 100644 index 00000000..035acca1 --- /dev/null +++ b/firmware/brake/kia_soul_ev/tests/features/step_definitions/common.cpp @@ -0,0 +1,145 @@ +#include +#include +#include +#include +#include + +#include "Arduino.h" +#include "communications.h" +#include "oscc_can.h" +#include "mcp_can.h" +#include "brake_control.h" +#include "can_protocols/fault_can_protocol.h" +#include "can_protocols/brake_can_protocol.h" +#include "globals.h" + +using namespace cgreen; + + +extern uint8_t g_mock_arduino_digital_write_pins[100]; +extern uint8_t g_mock_arduino_digital_write_val[100]; +extern int g_mock_arduino_digital_write_count; + +extern int g_mock_arduino_analog_read_return[100]; + +extern uint8_t g_mock_mcp_can_check_receive_return; +extern uint32_t g_mock_mcp_can_read_msg_buf_id; +extern uint8_t g_mock_mcp_can_read_msg_buf_buf[8]; +extern uint32_t g_mock_mcp_can_send_msg_buf_id; +extern uint8_t g_mock_mcp_can_send_msg_buf_ext; +extern uint8_t g_mock_mcp_can_send_msg_buf_len; +extern uint8_t *g_mock_mcp_can_send_msg_buf_buf; + +extern unsigned short g_mock_dac_output_a; +extern unsigned short g_mock_dac_output_b; + +extern volatile brake_control_state_s g_brake_control_state; + + +// return to known state before every scenario +BEFORE() +{ + g_mock_arduino_digital_write_count = 0; + memset(&g_mock_arduino_digital_write_pins, 0, sizeof(g_mock_arduino_digital_write_pins)); + memset(&g_mock_arduino_digital_write_val, 0, sizeof(g_mock_arduino_digital_write_val)); + + memset(&g_mock_arduino_analog_read_return, 0, sizeof(g_mock_arduino_analog_read_return)); + + g_mock_mcp_can_check_receive_return = UINT8_MAX; + g_mock_mcp_can_read_msg_buf_id = UINT32_MAX; + memset(&g_mock_mcp_can_read_msg_buf_buf, 0, sizeof(g_mock_mcp_can_read_msg_buf_buf)); + + g_mock_mcp_can_send_msg_buf_id = UINT32_MAX; + g_mock_mcp_can_send_msg_buf_ext = UINT8_MAX; + g_mock_mcp_can_send_msg_buf_len = UINT8_MAX; + + g_mock_dac_output_a = USHRT_MAX; + g_mock_dac_output_b = USHRT_MAX; + + g_brake_control_state.enabled = false; + g_brake_control_state.operator_override = false; + g_brake_control_state.dtcs = 0; +} + + +GIVEN("^brake control is enabled$") +{ + g_brake_control_state.enabled = 1; +} + + +GIVEN("^brake control is disabled$") +{ + g_brake_control_state.enabled = 0; +} + + +GIVEN("^the accelerator position sensors have a reading of (.*)$") +{ + REGEX_PARAM(int, sensor_val); + + g_mock_arduino_analog_read_return[0] = sensor_val; +} + + +GIVEN("^the operator has applied (.*) to the accelerator$") +{ + + REGEX_PARAM(int, brake_sensor_val); + + g_mock_arduino_analog_read_return[0] = brake_sensor_val; + + check_for_operator_override(); +} + + +THEN("^control should be enabled$") +{ + assert_that( + g_brake_control_state.enabled, + is_equal_to(1)); + + assert_that( + g_mock_arduino_digital_write_pins[0], + is_equal_to(PIN_SPOOF_ENABLE)); + + assert_that( + g_mock_arduino_digital_write_val[0], + is_equal_to(HIGH)); +} + + +THEN("^control should be disabled$") +{ + assert_that( + g_brake_control_state.enabled, + is_equal_to(0)); + + assert_that( + g_mock_arduino_digital_write_pins[0], + is_equal_to(PIN_SPOOF_ENABLE)); + + assert_that( + g_mock_arduino_digital_write_val[0], + is_equal_to(LOW)); +} + + +THEN("^(.*) should be sent to DAC A$") +{ + REGEX_PARAM(int, dac_output_a); + + assert_that( + g_mock_dac_output_a, + is_equal_to(dac_output_a)); +} + + +THEN("^(.*) should be sent to DAC B$") +{ + REGEX_PARAM(int, dac_output_b); + + assert_that( + g_mock_dac_output_b, + is_equal_to(dac_output_b)); +} diff --git a/firmware/brake/tests/features/step_definitions/cucumber.wire b/firmware/brake/kia_soul_ev/tests/features/step_definitions/cucumber.wire similarity index 100% rename from firmware/brake/tests/features/step_definitions/cucumber.wire rename to firmware/brake/kia_soul_ev/tests/features/step_definitions/cucumber.wire diff --git a/firmware/brake/kia_soul_ev/tests/features/step_definitions/receiving_messages.cpp b/firmware/brake/kia_soul_ev/tests/features/step_definitions/receiving_messages.cpp new file mode 100644 index 00000000..b298615c --- /dev/null +++ b/firmware/brake/kia_soul_ev/tests/features/step_definitions/receiving_messages.cpp @@ -0,0 +1,67 @@ +WHEN("^an enable brake command is received$") +{ + g_mock_mcp_can_read_msg_buf_id = OSCC_BRAKE_ENABLE_CAN_ID; + g_mock_mcp_can_check_receive_return = CAN_MSGAVAIL; + + oscc_brake_enable_s * brake_enable = + (oscc_brake_enable_s *) g_mock_mcp_can_read_msg_buf_buf; + + brake_enable->magic[0] = OSCC_MAGIC_BYTE_0; + brake_enable->magic[1] = OSCC_MAGIC_BYTE_1; + + check_for_incoming_message(); +} + + +WHEN("^a disable brake command is received$") +{ + g_mock_mcp_can_read_msg_buf_id = OSCC_BRAKE_DISABLE_CAN_ID; + g_mock_mcp_can_check_receive_return = CAN_MSGAVAIL; + + oscc_brake_disable_s * brake_disable = + (oscc_brake_disable_s *) g_mock_mcp_can_read_msg_buf_buf; + + brake_disable->magic[0] = OSCC_MAGIC_BYTE_0; + brake_disable->magic[1] = OSCC_MAGIC_BYTE_1; + + check_for_incoming_message(); +} + + +WHEN("^a fault report is received$") +{ + g_mock_mcp_can_check_receive_return = CAN_MSGAVAIL; + g_mock_mcp_can_read_msg_buf_id = OSCC_FAULT_REPORT_CAN_ID; + + oscc_fault_report_s * fault_report = + (oscc_fault_report_s *) g_mock_mcp_can_read_msg_buf_buf; + + fault_report->magic[0] = OSCC_MAGIC_BYTE_0; + fault_report->magic[1] = OSCC_MAGIC_BYTE_1; + + check_for_incoming_message(); +} + + +WHEN("^a command is received with spoof values (.*) and (.*)$") +{ + REGEX_PARAM(uint16_t, high); + REGEX_PARAM(uint16_t, low); + + g_mock_mcp_can_check_receive_return = CAN_MSGAVAIL; + g_mock_mcp_can_read_msg_buf_id = OSCC_BRAKE_COMMAND_CAN_ID; + + oscc_brake_command_s * brake_command = + (oscc_brake_command_s *) g_mock_mcp_can_read_msg_buf_buf; + + brake_command->magic[0] = OSCC_MAGIC_BYTE_0; + brake_command->magic[1] = OSCC_MAGIC_BYTE_1; + brake_command->spoof_value_high = high; + brake_command->spoof_value_low = low; + + check_for_incoming_message(); + + update_brake( + brake_command->spoof_value_high, + brake_command->spoof_value_low); +} diff --git a/firmware/brake/tests/features/step_definitions/sending_reports.cpp b/firmware/brake/kia_soul_ev/tests/features/step_definitions/sending_reports.cpp similarity index 100% rename from firmware/brake/tests/features/step_definitions/sending_reports.cpp rename to firmware/brake/kia_soul_ev/tests/features/step_definitions/sending_reports.cpp diff --git a/firmware/brake/tests/features/step_definitions/test.cpp b/firmware/brake/kia_soul_ev/tests/features/step_definitions/test.cpp similarity index 100% rename from firmware/brake/tests/features/step_definitions/test.cpp rename to firmware/brake/kia_soul_ev/tests/features/step_definitions/test.cpp diff --git a/firmware/brake/tests/features/support/env.rb b/firmware/brake/kia_soul_ev/tests/features/support/env.rb similarity index 100% rename from firmware/brake/tests/features/support/env.rb rename to firmware/brake/kia_soul_ev/tests/features/support/env.rb diff --git a/firmware/brake/kia_soul_ev/tests/property/Cargo.toml b/firmware/brake/kia_soul_ev/tests/property/Cargo.toml new file mode 100644 index 00000000..ffe54b1b --- /dev/null +++ b/firmware/brake/kia_soul_ev/tests/property/Cargo.toml @@ -0,0 +1,17 @@ +[package] +name = "brake_firmware_pb_tests" +version = "0.0.1" +authors = ["Katie Cleary "] +build = "build.rs" +description = "The manifest file for the brake module property-based tests. To run the tests, run the command 'cargo test -- --test-threads=1'" + +[dependencies] +quickcheck = "0.4.1" +rand = "0.3.15" + +[build-dependencies] +bindgen = "0.25.0" +gcc = "0.3.51" + +[lib] +name = "tests" diff --git a/firmware/brake/kia_soul_ev/tests/property/build.rs b/firmware/brake/kia_soul_ev/tests/property/build.rs new file mode 100644 index 00000000..5a008efb --- /dev/null +++ b/firmware/brake/kia_soul_ev/tests/property/build.rs @@ -0,0 +1,71 @@ +extern crate gcc; +extern crate bindgen; + +use std::env; +use std::path::Path; + +fn main() { + gcc::Config::new() + .flag("-w") + .define("KIA_SOUL_EV", Some("ON")) + .include("include") + .include("../../include") + .include("../../../../common/include") + .include("../../../../common/testing/mocks/") + .include("../../../../common/libs/can") + .include("../../../../common/libs/dac") + .include("../../../../../api/include") + .file("../../../../common/testing/mocks/Arduino_mock.cpp") + .file("../../../../common/testing/mocks/mcp_can_mock.cpp") + .file("../../../../common/testing/mocks/DAC_MCP49xx_mock.cpp") + .file("../../../../common/libs/can/oscc_can.cpp") + .file("../../../../common/libs/dac/oscc_dac.cpp") + .file("../../src/communications.cpp") + .file("../../src/brake_control.cpp") + .file("../../src/globals.cpp") + .cpp(true) + .compile("libbrake_test.a"); + + let out_dir = env::var("OUT_DIR").unwrap(); + + let _ = bindgen::builder() + .header("include/wrapper.hpp") + .generate_comments(false) + .layout_tests(false) + .clang_arg("-DKIA_SOUL_EV=ON") + .clang_arg("-I../../include") + .clang_arg("-I../../../../common/include") + .clang_arg("-I../../../../common/libs/can") + .clang_arg("-I../../../../common/testing/mocks") + .clang_arg("-I../../../../../api/include") + .whitelisted_function("publish_brake_report") + .whitelisted_function("check_for_incoming_message") + .whitelisted_function("check_for_operator_override") + .whitelisted_var("OSCC_MAGIC_BYTE_0") + .whitelisted_var("OSCC_MAGIC_BYTE_1") + .whitelisted_var("OSCC_BRAKE_ENABLE_CAN_ID") + .whitelisted_var("OSCC_BRAKE_DISABLE_CAN_ID") + .whitelisted_var("OSCC_BRAKE_REPORT_CAN_ID") + .whitelisted_var("OSCC_BRAKE_REPORT_CAN_DLC") + .whitelisted_var("OSCC_BRAKE_COMMAND_CAN_ID") + .whitelisted_var("OSCC_FAULT_REPORT_CAN_ID") + .whitelisted_var("OSCC_BRAKE_COMMAND_CAN_DLC") + .whitelisted_var("BRAKE_PEDAL_OVERRIDE_THRESHOLD") + .whitelisted_var("OSCC_BRAKE_REPORT_PUBLISH_INTERVAL_IN_MSEC") + .whitelisted_var("CAN_MSGAVAIL") + .whitelisted_var("CAN_STANDARD") + .whitelisted_var("BRAKE_SPOOF_LOW_SIGNAL_RANGE_MIN") + .whitelisted_var("BRAKE_SPOOF_LOW_SIGNAL_RANGE_MAX") + .whitelisted_var("BRAKE_SPOOF_HIGH_SIGNAL_RANGE_MIN") + .whitelisted_var("BRAKE_SPOOF_HIGH_SIGNAL_RANGE_MAX") + .whitelisted_type("oscc_brake_enable_s") + .whitelisted_type("oscc_brake_disable_s") + .whitelisted_type("oscc_brake_report_s") + .whitelisted_type("oscc_brake_command_s") + .whitelisted_type("can_frame_s") + .whitelisted_type("brake_control_state_s") + .generate() + .unwrap() + .write_to_file(Path::new(&out_dir).join("brake_test.rs")) + .expect("Unable to generate bindings"); +} diff --git a/firmware/brake/kia_soul_ev/tests/property/include/wrapper.hpp b/firmware/brake/kia_soul_ev/tests/property/include/wrapper.hpp new file mode 100644 index 00000000..8f73c05b --- /dev/null +++ b/firmware/brake/kia_soul_ev/tests/property/include/wrapper.hpp @@ -0,0 +1,7 @@ +#include "globals.h" +#include "communications.h" +#include "brake_control.h" +#include "oscc_can.h" +#include "can_protocols/brake_can_protocol.h" +#include "can_protocols/fault_can_protocol.h" +#include "vehicles.h" diff --git a/firmware/brake/kia_soul_ev/tests/property/src/tests.rs b/firmware/brake/kia_soul_ev/tests/property/src/tests.rs new file mode 100644 index 00000000..12b9b9f3 --- /dev/null +++ b/firmware/brake/kia_soul_ev/tests/property/src/tests.rs @@ -0,0 +1,307 @@ +#![allow(non_upper_case_globals)] +#![allow(non_camel_case_types)] +#![allow(non_snake_case)] +#![allow(dead_code)] +#![allow(unused_variables)] +#![allow(unused_imports)] +include!(concat!(env!("OUT_DIR"), "/brake_test.rs")); + +extern crate quickcheck; +extern crate rand; + +use quickcheck::{QuickCheck, TestResult, Arbitrary, StdGen, Gen}; +use rand::Rng; + +extern "C" { + pub static mut g_mock_mcp_can_check_receive_return: u8; + pub static mut g_mock_mcp_can_read_msg_buf_id: u32; + pub static mut g_mock_mcp_can_read_msg_buf_buf: [u8; 8usize]; + pub static mut g_mock_mcp_can_send_msg_buf_id: u32; + pub static mut g_mock_mcp_can_send_msg_buf_ext: u8; + pub static mut g_mock_mcp_can_send_msg_buf_len: u8; + pub static mut g_mock_mcp_can_send_msg_buf_buf: *mut u8; + pub static mut g_mock_arduino_analog_read_return: [isize; 8usize]; + pub static mut g_mock_dac_output_a: u16; + pub static mut g_mock_dac_output_b: u16; + pub static mut g_brake_control_state: brake_control_state_s; +} + +impl Arbitrary for oscc_brake_enable_s { + fn arbitrary(g: &mut G) -> oscc_brake_enable_s { + oscc_brake_enable_s { + magic: [OSCC_MAGIC_BYTE_0 as u8, OSCC_MAGIC_BYTE_1 as u8], + reserved: [u8::arbitrary(g); 6], + } + } +} + +impl Arbitrary for oscc_brake_disable_s { + fn arbitrary(g: &mut G) -> oscc_brake_disable_s { + oscc_brake_disable_s { + magic: [OSCC_MAGIC_BYTE_0 as u8, OSCC_MAGIC_BYTE_1 as u8], + reserved: [u8::arbitrary(g); 6], + } + } +} + +impl Arbitrary for oscc_brake_report_s { + fn arbitrary(g: &mut G) -> oscc_brake_report_s { + oscc_brake_report_s { + magic: [OSCC_MAGIC_BYTE_0 as u8, OSCC_MAGIC_BYTE_1 as u8], + enabled: u8::arbitrary(g), + operator_override: u8::arbitrary(g), + dtcs: u8::arbitrary(g), + reserved: [u8::arbitrary(g); 3] + } + } +} + +impl Arbitrary for oscc_brake_command_s { + fn arbitrary(g: &mut G) -> oscc_brake_command_s { + oscc_brake_command_s { + magic: [OSCC_MAGIC_BYTE_0 as u8, OSCC_MAGIC_BYTE_1 as u8], + spoof_value_low: u16::arbitrary(g), + spoof_value_high: u16::arbitrary(g), + reserved: [u8::arbitrary(g); 2] + } + } +} + +impl Arbitrary for can_frame_s { + fn arbitrary(g: &mut G) -> can_frame_s { + can_frame_s { + id: u32::arbitrary(g), + dlc: u8::arbitrary(g), + timestamp: u32::arbitrary(g), + data: [u8::arbitrary(g); 8] + } + } +} + +/// the brake firmware should not attempt processing any messages +/// that are not brake or fault commands +/// this means that none of the brake control state would +/// change, nor would it output any values onto the DAC. +fn prop_only_process_valid_messages(rx_can_msg: can_frame_s, enabled: bool, operator_override: bool, dtcs: u8) -> TestResult { + if rx_can_msg.id == OSCC_BRAKE_COMMAND_CAN_ID || + rx_can_msg.id == OSCC_FAULT_REPORT_CAN_ID + { + return TestResult::discard(); + } + unsafe { + let dac_a = g_mock_dac_output_a; + let dac_b = g_mock_dac_output_b; + g_brake_control_state.enabled = enabled; + g_brake_control_state.operator_override = operator_override; + g_brake_control_state.dtcs = dtcs; + + g_mock_mcp_can_read_msg_buf_id = rx_can_msg.id; + g_mock_mcp_can_read_msg_buf_buf = rx_can_msg.data; + g_mock_mcp_can_check_receive_return = CAN_MSGAVAIL as u8; + + check_for_incoming_message(); + + TestResult::from_bool(g_brake_control_state.enabled == enabled && + g_brake_control_state.operator_override == operator_override && + g_brake_control_state.dtcs == dtcs && + g_mock_dac_output_a == dac_a && + g_mock_dac_output_b == dac_b) + } +} + +#[test] +fn check_message_type_validity() { + QuickCheck::new() + .tests(1000) + .gen(StdGen::new(rand::thread_rng(), u32::max_value() as usize)) + .quickcheck(prop_only_process_valid_messages as fn(can_frame_s, bool, bool, u8) -> TestResult) +} + +/// the brake firmware should set the control state as enabled +/// upon receipt of a valid enable brake message telling it to enable +fn prop_process_enable_command(brake_enable_msg: oscc_brake_enable_s) -> TestResult { + unsafe { + g_brake_control_state.enabled = false; + g_brake_control_state.operator_override = false; + + g_mock_mcp_can_read_msg_buf_id = OSCC_BRAKE_ENABLE_CAN_ID; + g_mock_mcp_can_check_receive_return = CAN_MSGAVAIL as u8; + g_mock_mcp_can_read_msg_buf_buf = std::mem::transmute(brake_enable_msg); + + check_for_incoming_message(); + + TestResult::from_bool(g_brake_control_state.enabled == true) + } +} + +#[test] +fn check_process_enable_command() { + QuickCheck::new() + .tests(1000) + .quickcheck(prop_process_enable_command as fn(oscc_brake_enable_s) -> TestResult) +} + +/// the brake firmware should set the control state as disabled +/// upon receipt of a valid disable brake message telling it to disable +fn prop_process_disable_command(brake_disable_msg: oscc_brake_disable_s) -> TestResult { + unsafe { + g_brake_control_state.enabled = true; + g_brake_control_state.operator_override = false; + + g_mock_mcp_can_read_msg_buf_id = OSCC_BRAKE_DISABLE_CAN_ID; + g_mock_mcp_can_check_receive_return = CAN_MSGAVAIL as u8; + g_mock_mcp_can_read_msg_buf_buf = std::mem::transmute(brake_disable_msg); + + check_for_incoming_message(); + + TestResult::from_bool(g_brake_control_state.enabled == false) + } +} + +#[test] +fn check_process_disable_command() { + QuickCheck::new() + .tests(1000) + .quickcheck(prop_process_disable_command as fn(oscc_brake_disable_s) -> TestResult) +} + +/// the brake firmware should send requested spoof values +/// upon receiving a brake command message +fn prop_output_accurate_spoofs(mut brake_command_msg: oscc_brake_command_s) -> TestResult { + brake_command_msg.spoof_value_low = + rand::thread_rng().gen_range(BRAKE_SPOOF_LOW_SIGNAL_RANGE_MIN as u16, + BRAKE_SPOOF_LOW_SIGNAL_RANGE_MAX as u16); + brake_command_msg.spoof_value_high = + rand::thread_rng().gen_range(BRAKE_SPOOF_HIGH_SIGNAL_RANGE_MIN as u16, + BRAKE_SPOOF_HIGH_SIGNAL_RANGE_MAX as u16); + unsafe { + g_brake_control_state.enabled = true; + + g_mock_mcp_can_read_msg_buf_id = OSCC_BRAKE_COMMAND_CAN_ID; + g_mock_mcp_can_check_receive_return = CAN_MSGAVAIL as u8; + g_mock_mcp_can_read_msg_buf_buf = std::mem::transmute(brake_command_msg); + + check_for_incoming_message(); + + TestResult::from_bool(g_mock_dac_output_b == brake_command_msg.spoof_value_low && + g_mock_dac_output_a == brake_command_msg.spoof_value_high) + } +} + +#[test] +fn check_output_accurate_spoofs() { + QuickCheck::new() + .tests(1000) + .gen(StdGen::new(rand::thread_rng(), u16::max_value() as usize)) + .quickcheck(prop_output_accurate_spoofs as fn(oscc_brake_command_s) -> TestResult) +} + +/// the brake firmware should constrain requested spoof values +/// upon receiving a brake command message +fn prop_output_constrained_spoofs(brake_command_msg: oscc_brake_command_s) -> TestResult { + unsafe { + if (brake_command_msg.spoof_value_low >= BRAKE_SPOOF_LOW_SIGNAL_RANGE_MIN as u16 && + brake_command_msg.spoof_value_low <= BRAKE_SPOOF_LOW_SIGNAL_RANGE_MAX as u16) || + (brake_command_msg.spoof_value_high >= BRAKE_SPOOF_HIGH_SIGNAL_RANGE_MIN as u16 && + brake_command_msg.spoof_value_high <= BRAKE_SPOOF_HIGH_SIGNAL_RANGE_MAX as u16) { + return TestResult::discard(); + } + + g_brake_control_state.enabled = true; + + g_mock_mcp_can_read_msg_buf_id = OSCC_BRAKE_COMMAND_CAN_ID; + g_mock_mcp_can_check_receive_return = CAN_MSGAVAIL as u8; + g_mock_mcp_can_read_msg_buf_buf = std::mem::transmute(brake_command_msg); + + check_for_incoming_message(); + + TestResult::from_bool(g_mock_dac_output_a >= BRAKE_SPOOF_HIGH_SIGNAL_RANGE_MIN as u16 && + g_mock_dac_output_a <= BRAKE_SPOOF_HIGH_SIGNAL_RANGE_MAX as u16 && + g_mock_dac_output_b >= BRAKE_SPOOF_LOW_SIGNAL_RANGE_MIN as u16 && + g_mock_dac_output_b <= BRAKE_SPOOF_LOW_SIGNAL_RANGE_MAX as u16) + } +} + +#[test] +fn check_output_constrained_spoofs() { + QuickCheck::new() + .tests(1000) + .gen(StdGen::new(rand::thread_rng(), u16::max_value() as usize)) + .quickcheck(prop_output_constrained_spoofs as fn(oscc_brake_command_s) -> TestResult) +} + +/// the brake firmware should create only valid CAN frames +fn prop_send_valid_can_fields(enabled: bool, operator_override: bool, dtcs: u8) -> TestResult { + unsafe { + g_brake_control_state.operator_override = operator_override; + g_brake_control_state.enabled = enabled; + g_brake_control_state.dtcs = dtcs; + + publish_brake_report(); + + let brake_report_msg = g_mock_mcp_can_send_msg_buf_buf as *mut oscc_brake_report_s; + + TestResult::from_bool((*brake_report_msg).enabled == enabled as u8 && + (*brake_report_msg).operator_override == operator_override as u8 && + (*brake_report_msg).dtcs == dtcs) + } +} + +#[test] +fn check_valid_can_frame() { + QuickCheck::new() + .tests(10) + .gen(StdGen::new(rand::thread_rng(), u8::max_value() as usize)) + .quickcheck(prop_send_valid_can_fields as fn(bool, bool, u8) -> TestResult) +} + +// the brake firmware should be able to correctly and consistently +// detect operator overrides, disable on receipt, and send a fault report +fn prop_check_operator_override(analog_read_spoof: u16) -> TestResult { + unsafe { + g_brake_control_state.enabled = true; + g_brake_control_state.operator_override = false; + g_mock_arduino_analog_read_return[0] = analog_read_spoof as isize; + g_mock_arduino_analog_read_return[1] = analog_read_spoof as isize; + + check_for_operator_override(); + + if analog_read_spoof >= (BRAKE_PEDAL_OVERRIDE_THRESHOLD as u16) { + TestResult::from_bool(g_brake_control_state.operator_override == true && + g_brake_control_state.enabled == false && + g_mock_mcp_can_send_msg_buf_id == OSCC_FAULT_REPORT_CAN_ID) + } else { + TestResult::from_bool(g_brake_control_state.operator_override == false) + } + } +} + +#[test] +fn check_operator_override() { + QuickCheck::new() + .tests(1000) + .quickcheck(prop_check_operator_override as fn(u16) -> TestResult) +} + +/// the brake firmware should set disable itself when it receives a +/// fault report from any other module +fn prop_process_fault_command(enabled: bool, operator_override: bool) -> TestResult { + unsafe { + g_brake_control_state.enabled = enabled; + g_brake_control_state.operator_override = operator_override; + + g_mock_mcp_can_read_msg_buf_id = OSCC_FAULT_REPORT_CAN_ID; + g_mock_mcp_can_check_receive_return = CAN_MSGAVAIL as u8; + + check_for_incoming_message(); + + TestResult::from_bool(g_brake_control_state.enabled == false) + } +} + +#[test] +fn check_process_fault_command() { + QuickCheck::new() + .tests(1000) + .quickcheck(prop_process_fault_command as fn(bool, bool) -> TestResult) +} diff --git a/firmware/brake/kia_soul_petrol/CMakeLists.txt b/firmware/brake/kia_soul_petrol/CMakeLists.txt new file mode 100644 index 00000000..3c809742 --- /dev/null +++ b/firmware/brake/kia_soul_petrol/CMakeLists.txt @@ -0,0 +1,35 @@ +set(ARDUINO_DEFAULT_BOARD mega2560) + +generate_arduino_firmware( + brake + SRCS + ${CMAKE_SOURCE_DIR}/common/libs/arduino_init/arduino_init.cpp + ${CMAKE_SOURCE_DIR}/common/libs/mcp_can/mcp_can.cpp + ${CMAKE_SOURCE_DIR}/common/libs/pid/oscc_pid.cpp + ${CMAKE_SOURCE_DIR}/common/libs/serial/oscc_serial.cpp + ${CMAKE_SOURCE_DIR}/common/libs/can/oscc_can.cpp + ${CMAKE_SOURCE_DIR}/common/libs/timer/oscc_timer.cpp + src/main.cpp + src/globals.cpp + src/accumulator.cpp + src/helper.cpp + src/master_cylinder.cpp + src/brake_control.cpp + src/communications.cpp + src/init.cpp + src/timers.cpp) + +target_include_directories( + brake + PRIVATE + include + ${CMAKE_SOURCE_DIR}/common/include + ${CMAKE_SOURCE_DIR}/common/libs/arduino_init + ${CMAKE_SOURCE_DIR}/common/libs/mcp_can + ${CMAKE_SOURCE_DIR}/common/libs/pid + ${CMAKE_SOURCE_DIR}/common/libs/serial + ${CMAKE_SOURCE_DIR}/common/libs/can + ${CMAKE_SOURCE_DIR}/common/libs/timer + ${CMAKE_SOURCE_DIR}/../api/include) + +add_subdirectory(utils) diff --git a/firmware/brake/include/accumulator.h b/firmware/brake/kia_soul_petrol/include/accumulator.h similarity index 93% rename from firmware/brake/include/accumulator.h rename to firmware/brake/kia_soul_petrol/include/accumulator.h index ca2335e3..5bdc448b 100644 --- a/firmware/brake/include/accumulator.h +++ b/firmware/brake/kia_soul_petrol/include/accumulator.h @@ -5,8 +5,8 @@ */ -#ifndef _OSCC_KIA_SOUL_BRAKE_ACCUMULATOR_H_ -#define _OSCC_KIA_SOUL_BRAKE_ACCUMULATOR_H_ +#ifndef _OSCC_BRAKE_ACCUMULATOR_H_ +#define _OSCC_BRAKE_ACCUMULATOR_H_ // **************************************************************************** @@ -74,4 +74,4 @@ float accumulator_read_pressure( void ); void accumulator_maintain_pressure( void ); -#endif /* _OSCC_KIA_SOUL_BRAKE_ACCUMULATOR_H_ */ +#endif /* _OSCC_BRAKE_ACCUMULATOR_H_ */ diff --git a/firmware/brake/include/brake_control.h b/firmware/brake/kia_soul_petrol/include/brake_control.h similarity index 96% rename from firmware/brake/include/brake_control.h rename to firmware/brake/kia_soul_petrol/include/brake_control.h index 3c06ab5e..a4008173 100644 --- a/firmware/brake/include/brake_control.h +++ b/firmware/brake/kia_soul_petrol/include/brake_control.h @@ -5,8 +5,8 @@ */ -#ifndef _OSCC_KIA_SOUL_BRAKE_CONTROL_H_ -#define _OSCC_KIA_SOUL_BRAKE_CONTROL_H_ +#ifndef _OSCC_BRAKE_CONTROL_H_ +#define _OSCC_BRAKE_CONTROL_H_ #include @@ -145,4 +145,4 @@ void brake_init( void ); void update_brake( void ); -#endif /* _OSCC_KIA_SOUL_BRAKE_CONTROL_H_ */ +#endif /* _OSCC_BRAKE_CONTROL_H_ */ diff --git a/firmware/brake/kia_soul_petrol/include/communications.h b/firmware/brake/kia_soul_petrol/include/communications.h new file mode 100644 index 00000000..cdfbda44 --- /dev/null +++ b/firmware/brake/kia_soul_petrol/include/communications.h @@ -0,0 +1,64 @@ +/** + * @file communications.h + * @brief Communication functionality. + * + */ + + +#ifndef _OSCC_BRAKE_COMMUNICATIONS_H_ +#define _OSCC_BRAKE_COMMUNICATIONS_H_ + + +// **************************************************************************** +// Function: publish_brake_report +// +// Purpose: Publish brake report to CAN bus. +// +// Returns: void +// +// Parameters: void +// +// **************************************************************************** +void publish_brake_report( void ); + + +// **************************************************************************** +// Function: publish_fault_report +// +// Purpose: Publish a fault report message to the CAN bus. +// +// Returns: void +// +// Parameters: void +// +// **************************************************************************** +void publish_fault_report( void ); + + +// **************************************************************************** +// Function: check_for_controller_command_timeout +// +// Purpose: Check if the last command received from the controller exceeds +// the timeout and disable control if it does. +// +// Returns: void +// +// Parameters: void +// +// **************************************************************************** +void check_for_controller_command_timeout( void ); + +// **************************************************************************** +// Function: check_for_incoming_message +// +// Purpose: Check CAN bus for incoming messages and process any present. +// +// Returns: void +// +// Parameters: void +// +// **************************************************************************** +void check_for_incoming_message( void ); + + +#endif /* _OSCC_BRAKE_COMMUNICATIONS_H_ */ diff --git a/firmware/brake/include/globals.h b/firmware/brake/kia_soul_petrol/include/globals.h similarity index 95% rename from firmware/brake/include/globals.h rename to firmware/brake/kia_soul_petrol/include/globals.h index a42a956d..281ea3e8 100644 --- a/firmware/brake/include/globals.h +++ b/firmware/brake/kia_soul_petrol/include/globals.h @@ -5,15 +5,14 @@ */ -#ifndef _OSCC_KIA_SOUL_BRAKE_GLOBALS_H_ -#define _OSCC_KIA_SOUL_BRAKE_GLOBALS_H_ +#ifndef _OSCC_BRAKE_GLOBALS_H_ +#define _OSCC_BRAKE_GLOBALS_H_ +#include "brake_control.h" #include "mcp_can.h" #include "oscc_pid.h" -#include "brake_control.h" - /* * @brief Chip select pin of the CAN IC. @@ -150,4 +149,4 @@ EXTERN volatile brake_control_state_s g_brake_control_state; EXTERN pid_s g_pid; -#endif /* _OSCC_KIA_SOUL_BRAKE_GLOBALS_H_ */ +#endif /* _OSCC_BRAKE_GLOBALS_H_ */ diff --git a/firmware/brake/include/helper.h b/firmware/brake/kia_soul_petrol/include/helper.h similarity index 95% rename from firmware/brake/include/helper.h rename to firmware/brake/kia_soul_petrol/include/helper.h index dcc296bd..9284248a 100644 --- a/firmware/brake/include/helper.h +++ b/firmware/brake/kia_soul_petrol/include/helper.h @@ -5,8 +5,8 @@ */ -#ifndef _OSCC_KIA_SOUL_BRAKE_HELPER_H_ -#define _OSCC_KIA_SOUL_BRAKE_HELPER_H_ +#ifndef _OSCC_BRAKE_HELPER_H_ +#define _OSCC_BRAKE_HELPER_H_ #include @@ -94,4 +94,4 @@ float raw_adc_to_pressure( const int input ); -#endif /* _OSCC_KIA_SOUL_BRAKE_HELPER_H_ */ +#endif /* _OSCC_BRAKE_HELPER_H_ */ diff --git a/firmware/brake/kia_soul_petrol/include/init.h b/firmware/brake/kia_soul_petrol/include/init.h new file mode 100644 index 00000000..df8f22d1 --- /dev/null +++ b/firmware/brake/kia_soul_petrol/include/init.h @@ -0,0 +1,51 @@ +/** + * @file init.h + * @brief Initialization functionality. + * + */ + + +#ifndef _OSCC_BRAKE_INIT_H_ +#define _OSCC_BRAKE_INIT_H_ + + +// **************************************************************************** +// Function: init_globals +// +// Purpose: Initialize values of global variables. +// +// Returns: void +// +// Parameters: void +// +// **************************************************************************** +void init_globals( void ); + + +// **************************************************************************** +// Function: init_devices +// +// Purpose: Initialize physical devices on or connected to the module. +// +// Returns: void +// +// Parameters: void +// +// **************************************************************************** +void init_devices( void ); + + +// **************************************************************************** +// Function: init_communication_interfaces +// +// Purpose: Initialize the communication interfaces used by the module. +// +// Returns: void +// +// Parameters: void +// +// **************************************************************************** +void init_communication_interfaces( void ); + + +#endif /* _OSCC_BRAKE_INIT_H_ */ diff --git a/firmware/brake/include/master_cylinder.h b/firmware/brake/kia_soul_petrol/include/master_cylinder.h similarity index 92% rename from firmware/brake/include/master_cylinder.h rename to firmware/brake/kia_soul_petrol/include/master_cylinder.h index f983bdff..5f815254 100644 --- a/firmware/brake/include/master_cylinder.h +++ b/firmware/brake/kia_soul_petrol/include/master_cylinder.h @@ -5,8 +5,8 @@ */ -#ifndef _OSCC_KIA_SOUL_BRAKE_MASTER_CYLINDER_H_ -#define _OSCC_KIA_SOUL_BRAKE_MASTER_CYLINDER_H_ +#ifndef _OSCC_BRAKE_MASTER_CYLINDER_H_ +#define _OSCC_BRAKE_MASTER_CYLINDER_H_ typedef struct @@ -69,4 +69,4 @@ void master_cylinder_init( void ); void master_cylinder_read_pressure( master_cylinder_pressure_s * pressure ); -#endif /* _OSCC_KIA_SOUL_BRAKE_MASTER_CYLINDER_H_ */ +#endif /* _OSCC_BRAKE_MASTER_CYLINDER_H_ */ diff --git a/firmware/brake/kia_soul_petrol/include/timers.h b/firmware/brake/kia_soul_petrol/include/timers.h new file mode 100644 index 00000000..7ce05c90 --- /dev/null +++ b/firmware/brake/kia_soul_petrol/include/timers.h @@ -0,0 +1,25 @@ +/** + * @file timers.h + * @brief Timer functionality. + * + */ + + +#ifndef _OSCC_BRAKE_TIMERS_H_ +#define _OSCC_BRAKE_TIMERS_H_ + + +// **************************************************************************** +// Function: start_timers +// +// Purpose: Start timers for report publishing and fault checking. +// +// Returns: void +// +// Parameters: void +// +// **************************************************************************** +void start_timers( void ); + + +#endif /* _OSCC_BRAKE_TIMERS_H_ */ diff --git a/firmware/brake/src/accumulator.cpp b/firmware/brake/kia_soul_petrol/src/accumulator.cpp similarity index 100% rename from firmware/brake/src/accumulator.cpp rename to firmware/brake/kia_soul_petrol/src/accumulator.cpp index 6cf745f5..88e44e16 100644 --- a/firmware/brake/src/accumulator.cpp +++ b/firmware/brake/kia_soul_petrol/src/accumulator.cpp @@ -5,12 +5,12 @@ #include -#include "vehicles.h" -#include "globals.h" #include "accumulator.h" -#include "helper.h" #include "debug.h" +#include "globals.h" +#include "helper.h" +#include "vehicles.h" void accumulator_init( void ) diff --git a/firmware/brake/src/brake_control.cpp b/firmware/brake/kia_soul_petrol/src/brake_control.cpp similarity index 96% rename from firmware/brake/src/brake_control.cpp rename to firmware/brake/kia_soul_petrol/src/brake_control.cpp index 15d9ffb9..0779fd9f 100644 --- a/firmware/brake/src/brake_control.cpp +++ b/firmware/brake/kia_soul_petrol/src/brake_control.cpp @@ -4,18 +4,20 @@ */ -#include "debug.h" -#include "oscc_pid.h" -#include "dtc.h" -#include "can_protocols/brake_can_protocol.h" -#include "vehicles.h" +#include +#include -#include "globals.h" #include "accumulator.h" #include "brake_control.h" +#include "can_protocols/brake_can_protocol.h" #include "communications.h" -#include "master_cylinder.h" +#include "debug.h" +#include "dtc.h" +#include "globals.h" #include "helper.h" +#include "master_cylinder.h" +#include "oscc_pid.h" +#include "vehicles.h" /* @@ -39,15 +41,19 @@ static void pump_startup_check( void ); void set_accumulator_solenoid_duty_cycle( const uint16_t duty_cycle ) { + cli(); analogWrite( PIN_ACCUMULATOR_SOLENOID_FRONT_LEFT, duty_cycle ); analogWrite( PIN_ACCUMULATOR_SOLENOID_FRONT_RIGHT, duty_cycle ); + sei(); } void set_release_solenoid_duty_cycle( const uint16_t duty_cycle ) { + cli(); analogWrite( PIN_RELEASE_SOLENOID_FRONT_LEFT, duty_cycle ); analogWrite( PIN_RELEASE_SOLENOID_FRONT_RIGHT, duty_cycle ); + sei(); } @@ -62,6 +68,7 @@ void enable_control( void ) set_release_solenoid_duty_cycle( SOLENOID_PWM_OFF ); + g_brake_command_timeout = false; g_brake_control_state.enabled = true; DEBUG_PRINTLN( "Control enabled" ); @@ -85,6 +92,7 @@ void disable_control( void ) set_release_solenoid_duty_cycle( SOLENOID_PWM_OFF ); + g_brake_command_timeout = false; g_brake_control_state.enabled = false; DEBUG_PRINTLN( "Control disabled" ); @@ -106,6 +114,10 @@ void check_for_operator_override( void ) { disable_control( ); + DTC_SET( + g_brake_control_state.dtcs, + OSCC_BRAKE_DTC_OPERATOR_OVERRIDE ); + publish_fault_report( ); g_brake_control_state.operator_override = true; @@ -114,6 +126,10 @@ void check_for_operator_override( void ) } else { + DTC_CLEAR( + g_brake_control_state.dtcs, + OSCC_BRAKE_DTC_OPERATOR_OVERRIDE ); + g_brake_control_state.operator_override = false; } } @@ -158,11 +174,11 @@ void check_for_sensor_faults( void ) { disable_control( ); - publish_fault_report( ); - DTC_SET( g_brake_control_state.dtcs, OSCC_BRAKE_DTC_INVALID_SENSOR_VAL ); + + publish_fault_report( ); } else { @@ -479,7 +495,9 @@ static void pump_startup_check( void ) accumulator_turn_pump_on(); delay(250); + cli(); int motor_check = analogRead( PIN_ACCUMULATOR_PUMP_MOTOR_CHECK ); + sei(); // should not be 0 if the pump is on if( motor_check == 0 ) diff --git a/firmware/brake/src/communications.cpp b/firmware/brake/kia_soul_petrol/src/communications.cpp similarity index 84% rename from firmware/brake/src/communications.cpp rename to firmware/brake/kia_soul_petrol/src/communications.cpp index 6d84f756..08a3cc7a 100644 --- a/firmware/brake/src/communications.cpp +++ b/firmware/brake/kia_soul_petrol/src/communications.cpp @@ -4,15 +4,17 @@ */ -#include "mcp_can.h" +#include +#include + +#include "brake_control.h" #include "can_protocols/brake_can_protocol.h" #include "can_protocols/fault_can_protocol.h" -#include "oscc_can.h" +#include "communications.h" #include "debug.h" - #include "globals.h" -#include "communications.h" -#include "brake_control.h" +#include "mcp_can.h" +#include "oscc_can.h" static void process_rx_frame( @@ -52,6 +54,7 @@ void publish_fault_report( void ) fault_report.magic[0] = (uint8_t) OSCC_MAGIC_BYTE_0; fault_report.magic[1] = (uint8_t) OSCC_MAGIC_BYTE_1; fault_report.fault_origin_id = FAULT_ORIGIN_BRAKE; + fault_report.dtcs = g_brake_control_state.dtcs; cli(); g_control_can.sendMsgBuf( @@ -99,7 +102,15 @@ static void process_rx_frame( if( (frame->data[0] == OSCC_MAGIC_BYTE_0) && (frame->data[1] == OSCC_MAGIC_BYTE_1) ) { - if ( frame->id == OSCC_BRAKE_COMMAND_CAN_ID ) + if ( frame->id == OSCC_BRAKE_ENABLE_CAN_ID ) + { + enable_control( ); + } + else if ( frame->id == OSCC_BRAKE_DISABLE_CAN_ID ) + { + disable_control( ); + } + else if ( frame->id == OSCC_BRAKE_COMMAND_CAN_ID ) { process_brake_command( frame->data ); } @@ -120,15 +131,6 @@ static void process_brake_command( const oscc_brake_command_s * const brake_command = (oscc_brake_command_s *) data; - if( brake_command->enable == true ) - { - enable_control( ); - } - else - { - disable_control( ); - } - g_brake_control_state.commanded_pedal_position = brake_command->pedal_command; @@ -147,6 +149,9 @@ static void process_fault_report( disable_control( ); - DEBUG_PRINTLN( "Fault report received" ); + DEBUG_PRINT( "Fault report received from: " ); + DEBUG_PRINT( fault_report->fault_origin_id ); + DEBUG_PRINT( " DTCs: "); + DEBUG_PRINTLN( fault_report->dtcs ); } } diff --git a/firmware/brake/src/globals.cpp b/firmware/brake/kia_soul_petrol/src/globals.cpp similarity index 100% rename from firmware/brake/src/globals.cpp rename to firmware/brake/kia_soul_petrol/src/globals.cpp diff --git a/firmware/brake/src/helper.cpp b/firmware/brake/kia_soul_petrol/src/helper.cpp similarity index 97% rename from firmware/brake/src/helper.cpp rename to firmware/brake/kia_soul_petrol/src/helper.cpp index 22a293bf..84a11b8f 100644 --- a/firmware/brake/src/helper.cpp +++ b/firmware/brake/kia_soul_petrol/src/helper.cpp @@ -4,12 +4,11 @@ */ -#include #include -#include "vehicles.h" #include "globals.h" #include "helper.h" +#include "vehicles.h" float interpolate( diff --git a/firmware/brake/src/init.cpp b/firmware/brake/kia_soul_petrol/src/init.cpp similarity index 100% rename from firmware/brake/src/init.cpp rename to firmware/brake/kia_soul_petrol/src/init.cpp index 71260419..20352326 100644 --- a/firmware/brake/src/init.cpp +++ b/firmware/brake/kia_soul_petrol/src/init.cpp @@ -5,19 +5,19 @@ #include -#include "oscc_serial.h" -#include "oscc_can.h" -#include "debug.h" -#include "oscc_timer.h" -#include "can_protocols/brake_can_protocol.h" -#include "vehicles.h" +#include "accumulator.h" +#include "brake_control.h" +#include "can_protocols/brake_can_protocol.h" +#include "communications.h" +#include "debug.h" #include "globals.h" #include "init.h" -#include "communications.h" -#include "accumulator.h" #include "master_cylinder.h" -#include "brake_control.h" +#include "oscc_can.h" +#include "oscc_serial.h" +#include "oscc_timer.h" +#include "vehicles.h" void init_globals( void ) diff --git a/firmware/brake/src/main.cpp b/firmware/brake/kia_soul_petrol/src/main.cpp similarity index 91% rename from firmware/brake/src/main.cpp rename to firmware/brake/kia_soul_petrol/src/main.cpp index 8e4ed040..cc48d32b 100644 --- a/firmware/brake/src/main.cpp +++ b/firmware/brake/kia_soul_petrol/src/main.cpp @@ -4,14 +4,13 @@ */ -#include "arduino_init.h" - -#include "debug.h" #include "accumulator.h" +#include "arduino_init.h" #include "brake_control.h" #include "communications.h" -#include "timers.h" +#include "debug.h" #include "init.h" +#include "timers.h" int main( void ) @@ -28,7 +27,7 @@ int main( void ) start_timers( ); - DEBUG_PRINTLN( "initialization complete" ); + DEBUG_PRINTLN( "init complete" ); while( true ) { diff --git a/firmware/brake/src/master_cylinder.cpp b/firmware/brake/kia_soul_petrol/src/master_cylinder.cpp similarity index 100% rename from firmware/brake/src/master_cylinder.cpp rename to firmware/brake/kia_soul_petrol/src/master_cylinder.cpp index 739734f2..119dd576 100644 --- a/firmware/brake/src/master_cylinder.cpp +++ b/firmware/brake/kia_soul_petrol/src/master_cylinder.cpp @@ -5,8 +5,8 @@ #include -#include "debug.h" +#include "debug.h" #include "globals.h" #include "helper.h" #include "master_cylinder.h" diff --git a/firmware/brake/src/timers.cpp b/firmware/brake/kia_soul_petrol/src/timers.cpp similarity index 97% rename from firmware/brake/src/timers.cpp rename to firmware/brake/kia_soul_petrol/src/timers.cpp index 545c64f1..bec06cac 100644 --- a/firmware/brake/src/timers.cpp +++ b/firmware/brake/kia_soul_petrol/src/timers.cpp @@ -4,13 +4,14 @@ */ -#include "can_protocols/brake_can_protocol.h" -#include "oscc_timer.h" +#include -#include "timers.h" #include "globals.h" -#include "communications.h" #include "brake_control.h" +#include "can_protocols/brake_can_protocol.h" +#include "communications.h" +#include "oscc_timer.h" +#include "timers.h" /* diff --git a/firmware/brake/tests/CMakeLists.txt b/firmware/brake/kia_soul_petrol/tests/CMakeLists.txt similarity index 100% rename from firmware/brake/tests/CMakeLists.txt rename to firmware/brake/kia_soul_petrol/tests/CMakeLists.txt diff --git a/firmware/brake/tests/features/checking_faults.feature b/firmware/brake/kia_soul_petrol/tests/features/checking_faults.feature similarity index 100% rename from firmware/brake/tests/features/checking_faults.feature rename to firmware/brake/kia_soul_petrol/tests/features/checking_faults.feature diff --git a/firmware/brake/tests/features/receiving_messages.feature b/firmware/brake/kia_soul_petrol/tests/features/receiving_messages.feature similarity index 100% rename from firmware/brake/tests/features/receiving_messages.feature rename to firmware/brake/kia_soul_petrol/tests/features/receiving_messages.feature diff --git a/firmware/brake/tests/features/sending_reports.feature b/firmware/brake/kia_soul_petrol/tests/features/sending_reports.feature similarity index 100% rename from firmware/brake/tests/features/sending_reports.feature rename to firmware/brake/kia_soul_petrol/tests/features/sending_reports.feature diff --git a/firmware/brake/tests/features/step_definitions/checking_faults.cpp b/firmware/brake/kia_soul_petrol/tests/features/step_definitions/checking_faults.cpp similarity index 83% rename from firmware/brake/tests/features/step_definitions/checking_faults.cpp rename to firmware/brake/kia_soul_petrol/tests/features/step_definitions/checking_faults.cpp index fc333958..9581dbfa 100644 --- a/firmware/brake/tests/features/step_definitions/checking_faults.cpp +++ b/firmware/brake/kia_soul_petrol/tests/features/step_definitions/checking_faults.cpp @@ -1,6 +1,7 @@ WHEN("^a sensor becomes temporarily disconnected$") { - g_mock_arduino_analog_read_return = 0; + g_mock_arduino_analog_read_return[0] = 0; + g_mock_arduino_analog_read_return[1] = 0; check_for_sensor_faults(); @@ -12,7 +13,8 @@ WHEN("^a sensor becomes temporarily disconnected$") WHEN("^a sensor becomes permanently disconnected$") { - g_mock_arduino_analog_read_return = 0; + g_mock_arduino_analog_read_return[0] = 0; + g_mock_arduino_analog_read_return[1] = 0; // must call function enough times to exceed the fault limit for( int i = 0; i < 100; ++i ) @@ -34,7 +36,8 @@ WHEN("^the operator applies (.*) to the brake pedal$") { REGEX_PARAM(int, pedal_val); - g_mock_arduino_analog_read_return = pedal_val; + g_mock_arduino_analog_read_return[10] = pedal_val; + g_mock_arduino_analog_read_return[11] = pedal_val; check_for_operator_override(); diff --git a/firmware/brake/tests/features/step_definitions/common.cpp b/firmware/brake/kia_soul_petrol/tests/features/step_definitions/common.cpp similarity index 88% rename from firmware/brake/tests/features/step_definitions/common.cpp rename to firmware/brake/kia_soul_petrol/tests/features/step_definitions/common.cpp index 69e12257..db167b02 100644 --- a/firmware/brake/tests/features/step_definitions/common.cpp +++ b/firmware/brake/kia_soul_petrol/tests/features/step_definitions/common.cpp @@ -18,10 +18,11 @@ using namespace cgreen; extern unsigned long g_mock_arduino_micros_return; -extern uint8_t g_mock_arduino_digital_write_pin; -extern uint8_t g_mock_arduino_digital_write_val; +extern uint8_t g_mock_arduino_digital_write_pins[100]; +extern uint8_t g_mock_arduino_digital_write_val[100]; +extern int g_mock_arduino_digital_write_count; -extern int g_mock_arduino_analog_read_return; +extern int g_mock_arduino_analog_read_return[100]; extern int g_mock_arduino_analog_write_count; extern uint8_t g_mock_arduino_analog_write_pins[100]; extern int g_mock_arduino_analog_write_val[100]; @@ -40,10 +41,11 @@ extern volatile brake_control_state_s g_brake_control_state; // return to known state before every scenario BEFORE() { - g_mock_arduino_digital_write_pin = UINT8_MAX; - g_mock_arduino_digital_write_val = UINT8_MAX; + g_mock_arduino_digital_write_count = 0; + memset(&g_mock_arduino_digital_write_pins, 0, sizeof(g_mock_arduino_digital_write_pins)); + memset(&g_mock_arduino_digital_write_val, 0, sizeof(g_mock_arduino_digital_write_val)); - g_mock_arduino_analog_read_return = INT_MAX; + g_mock_arduino_analog_read_return[0] = INT_MAX; g_mock_arduino_analog_write_count = 0; memset(&g_mock_arduino_analog_write_pins, 0, sizeof(g_mock_arduino_analog_write_pins)); memset(&g_mock_arduino_analog_write_val, 0, sizeof(g_mock_arduino_analog_write_val)); @@ -148,11 +150,11 @@ THEN("^control should be disabled$") // turn brake lights off assert_that( - g_mock_arduino_digital_write_pin, + g_mock_arduino_digital_write_pins[0], is_equal_to(PIN_BRAKE_LIGHT)); assert_that( - g_mock_arduino_digital_write_val, + g_mock_arduino_digital_write_val[0], is_equal_to(LOW)); // open master cylinder diff --git a/firmware/brake/kia_soul_petrol/tests/features/step_definitions/cucumber.wire b/firmware/brake/kia_soul_petrol/tests/features/step_definitions/cucumber.wire new file mode 100644 index 00000000..da2da560 --- /dev/null +++ b/firmware/brake/kia_soul_petrol/tests/features/step_definitions/cucumber.wire @@ -0,0 +1,2 @@ +host: localhost +port: 3902 diff --git a/firmware/brake/tests/features/step_definitions/receiving_messages.cpp b/firmware/brake/kia_soul_petrol/tests/features/step_definitions/receiving_messages.cpp similarity index 88% rename from firmware/brake/tests/features/step_definitions/receiving_messages.cpp rename to firmware/brake/kia_soul_petrol/tests/features/step_definitions/receiving_messages.cpp index 29e4f86b..73b92ec3 100644 --- a/firmware/brake/tests/features/step_definitions/receiving_messages.cpp +++ b/firmware/brake/kia_soul_petrol/tests/features/step_definitions/receiving_messages.cpp @@ -11,7 +11,7 @@ GIVEN("^the left brake sensor reads (.*)$") { REGEX_PARAM(int, sensor_val); - g_mock_arduino_analog_read_return = sensor_val; + g_mock_arduino_analog_read_return[14] = sensor_val; } @@ -19,21 +19,20 @@ GIVEN("^the right brake sensor reads (.*)$") { REGEX_PARAM(int, sensor_val); - g_mock_arduino_analog_read_return = sensor_val; + g_mock_arduino_analog_read_return[13] = sensor_val; } WHEN("^an enable brake command is received$") { - g_mock_mcp_can_read_msg_buf_id = OSCC_BRAKE_COMMAND_CAN_ID; + g_mock_mcp_can_read_msg_buf_id = OSCC_BRAKE_ENABLE_CAN_ID; g_mock_mcp_can_check_receive_return = CAN_MSGAVAIL; - oscc_brake_command_s * brake_command = - (oscc_brake_command_s *) g_mock_mcp_can_read_msg_buf_buf; + oscc_brake_enable_s * brake_enable = + (oscc_brake_enable_s *) g_mock_mcp_can_read_msg_buf_buf; - brake_command->magic[0] = OSCC_MAGIC_BYTE_0; - brake_command->magic[1] = OSCC_MAGIC_BYTE_1; - brake_command->enable = 1; + brake_enable->magic[0] = OSCC_MAGIC_BYTE_0; + brake_enable->magic[1] = OSCC_MAGIC_BYTE_1; check_for_incoming_message(); } @@ -41,15 +40,14 @@ WHEN("^an enable brake command is received$") WHEN("^a disable brake command is received$") { - g_mock_mcp_can_read_msg_buf_id = OSCC_BRAKE_COMMAND_CAN_ID; + g_mock_mcp_can_read_msg_buf_id = OSCC_BRAKE_DISABLE_CAN_ID; g_mock_mcp_can_check_receive_return = CAN_MSGAVAIL; - oscc_brake_command_s * brake_command = - (oscc_brake_command_s *) g_mock_mcp_can_read_msg_buf_buf; + oscc_brake_disable_s * brake_disable = + (oscc_brake_disable_s *) g_mock_mcp_can_read_msg_buf_buf; - brake_command->magic[0] = OSCC_MAGIC_BYTE_0; - brake_command->magic[1] = OSCC_MAGIC_BYTE_1; - brake_command->enable = 0; + brake_disable->magic[0] = OSCC_MAGIC_BYTE_0; + brake_disable->magic[1] = OSCC_MAGIC_BYTE_1; check_for_incoming_message(); } @@ -82,7 +80,6 @@ WHEN("^the brake pedal command (.*) is received$") brake_command->magic[0] = OSCC_MAGIC_BYTE_0; brake_command->magic[1] = OSCC_MAGIC_BYTE_1; - brake_command->enable = 1; brake_command->pedal_command = command; pid_zeroize( &g_pid, BRAKE_PID_WINDUP_GUARD ); diff --git a/firmware/brake/kia_soul_petrol/tests/features/step_definitions/sending_reports.cpp b/firmware/brake/kia_soul_petrol/tests/features/step_definitions/sending_reports.cpp new file mode 100644 index 00000000..dd073107 --- /dev/null +++ b/firmware/brake/kia_soul_petrol/tests/features/step_definitions/sending_reports.cpp @@ -0,0 +1,43 @@ +WHEN("^a brake report is published$") +{ + g_brake_control_state.enabled = true; + g_brake_control_state.operator_override = true; + g_brake_control_state.dtcs = 0x55; + + publish_brake_report(); +} + + +THEN("^a brake report should be put on the control CAN bus$") +{ + assert_that(g_mock_mcp_can_send_msg_buf_id, is_equal_to(OSCC_BRAKE_REPORT_CAN_ID)); + assert_that(g_mock_mcp_can_send_msg_buf_ext, is_equal_to(CAN_STANDARD)); + assert_that(g_mock_mcp_can_send_msg_buf_len, is_equal_to(OSCC_BRAKE_REPORT_CAN_DLC)); +} + + +THEN("^the brake report's fields should be set$") +{ + oscc_brake_report_s * brake_report = + (oscc_brake_report_s *) g_mock_mcp_can_send_msg_buf_buf; + + assert_that( + brake_report->magic[0], + is_equal_to(OSCC_MAGIC_BYTE_0)); + + assert_that( + brake_report->magic[1], + is_equal_to(OSCC_MAGIC_BYTE_1)); + + assert_that( + brake_report->enabled, + is_equal_to(g_brake_control_state.enabled)); + + assert_that( + brake_report->operator_override, + is_equal_to(g_brake_control_state.operator_override)); + + assert_that( + brake_report->dtcs, + is_equal_to(g_brake_control_state.dtcs)); +} diff --git a/firmware/brake/kia_soul_petrol/tests/features/step_definitions/test.cpp b/firmware/brake/kia_soul_petrol/tests/features/step_definitions/test.cpp new file mode 100644 index 00000000..5f7d398e --- /dev/null +++ b/firmware/brake/kia_soul_petrol/tests/features/step_definitions/test.cpp @@ -0,0 +1,5 @@ +// include source files to prevent step files from conflicting with each other +#include "common.cpp" +#include "checking_faults.cpp" +#include "receiving_messages.cpp" +#include "sending_reports.cpp" diff --git a/firmware/brake/kia_soul_petrol/tests/features/support/env.rb b/firmware/brake/kia_soul_petrol/tests/features/support/env.rb new file mode 100644 index 00000000..e69de29b diff --git a/firmware/brake/tests/property/Cargo.toml b/firmware/brake/kia_soul_petrol/tests/property/Cargo.toml similarity index 100% rename from firmware/brake/tests/property/Cargo.toml rename to firmware/brake/kia_soul_petrol/tests/property/Cargo.toml diff --git a/firmware/brake/tests/property/build.rs b/firmware/brake/kia_soul_petrol/tests/property/build.rs similarity index 66% rename from firmware/brake/tests/property/build.rs rename to firmware/brake/kia_soul_petrol/tests/property/build.rs index 421221d3..5246878a 100644 --- a/firmware/brake/tests/property/build.rs +++ b/firmware/brake/kia_soul_petrol/tests/property/build.rs @@ -10,23 +10,21 @@ fn main() { .define("KIA_SOUL", Some("ON")) .include("include") .include("../../include") - .include("../../../common/testing/mocks") - .include("../../../common/include") - .include("../../../common/libs/can") - .include("../../../common/libs/time") - .include("../../../common/libs/pid") - .include("../../../../api/include") - .include("/usr/include") - .file("../../../common/testing/mocks/Arduino_mock.cpp") - .file("../../../common/testing/mocks/mcp_can_mock.cpp") + .include("../../../../common/testing/mocks") + .include("../../../../common/include") + .include("../../../../common/libs/can") + .include("../../../../common/libs/time") + .include("../../../../common/libs/pid") + .include("../../../../../api/include") + .file("../../../../common/testing/mocks/Arduino_mock.cpp") + .file("../../../../common/testing/mocks/mcp_can_mock.cpp") .file("../../src/communications.cpp") .file("../../src/brake_control.cpp") .file("../../src/globals.cpp") .file("../../src/master_cylinder.cpp") .file("../../src/helper.cpp") - .file("../../../common/libs/can/oscc_can.cpp") + .file("../../../../common/libs/can/oscc_can.cpp") .cpp(true) - .compiler("/usr/bin/g++") .compile("libbrake_test.a"); let out_dir = env::var("OUT_DIR").unwrap(); @@ -36,16 +34,18 @@ fn main() { .generate_comments(false) .clang_arg("-DKIA_SOUL=ON") .clang_arg("-I../../include") - .clang_arg("-I../../../common/testing/mocks") - .clang_arg("-I../../../common/include") - .clang_arg("-I../../../common/libs/can") - .clang_arg("-I../../../common/libs/pid") - .clang_arg("-I../../../../api/include") + .clang_arg("-I../../../../common/testing/mocks") + .clang_arg("-I../../../../common/include") + .clang_arg("-I../../../../common/libs/can") + .clang_arg("-I../../../../common/libs/pid") + .clang_arg("-I../../../../../api/include") .whitelisted_function("publish_brake_report") .whitelisted_function("check_for_incoming_message") .whitelisted_function("check_for_operator_override") .whitelisted_var("OSCC_MAGIC_BYTE_0") .whitelisted_var("OSCC_MAGIC_BYTE_1") + .whitelisted_var("OSCC_BRAKE_ENABLE_CAN_ID") + .whitelisted_var("OSCC_BRAKE_DISABLE_CAN_ID") .whitelisted_var("OSCC_BRAKE_REPORT_CAN_ID") .whitelisted_var("OSCC_BRAKE_REPORT_CAN_DLC") .whitelisted_var("OSCC_BRAKE_COMMAND_CAN_ID") @@ -57,6 +57,8 @@ fn main() { .whitelisted_var("CAN_MSGAVAIL") .whitelisted_var("g_control_can") .whitelisted_var("g_brake_control_state") + .whitelisted_type("oscc_brake_enable_s") + .whitelisted_type("oscc_brake_disable_s") .whitelisted_type("oscc_brake_report_s") .whitelisted_type("oscc_brake_command_s") .whitelisted_type("can_frame_s") diff --git a/firmware/brake/tests/property/include/wrapper.hpp b/firmware/brake/kia_soul_petrol/tests/property/include/wrapper.hpp similarity index 100% rename from firmware/brake/tests/property/include/wrapper.hpp rename to firmware/brake/kia_soul_petrol/tests/property/include/wrapper.hpp diff --git a/firmware/brake/tests/property/src/tests.rs b/firmware/brake/kia_soul_petrol/tests/property/src/tests.rs similarity index 68% rename from firmware/brake/tests/property/src/tests.rs rename to firmware/brake/kia_soul_petrol/tests/property/src/tests.rs index e8c6f237..3b67a164 100644 --- a/firmware/brake/tests/property/src/tests.rs +++ b/firmware/brake/kia_soul_petrol/tests/property/src/tests.rs @@ -12,24 +12,34 @@ extern crate rand; use quickcheck::{QuickCheck, TestResult, Arbitrary, Gen, StdGen}; extern "C" { - #[link_name = "g_mock_mcp_can_check_receive_return"] pub static mut g_mock_mcp_can_check_receive_return: u8; - #[link_name = "g_mock_mcp_can_read_msg_buf_id"] pub static mut g_mock_mcp_can_read_msg_buf_id: u32; - #[link_name = "g_mock_mcp_can_read_msg_buf_buf"] pub static mut g_mock_mcp_can_read_msg_buf_buf: [u8; 8usize]; - #[link_name = "g_mock_mcp_can_send_msg_buf_id"] pub static mut g_mock_mcp_can_send_msg_buf_id: u32; - #[link_name = "g_mock_mcp_can_send_msg_buf_ext"] pub static mut g_mock_mcp_can_send_msg_buf_ext: u8; - #[link_name = "g_mock_mcp_can_send_msg_buf_len"] pub static mut g_mock_mcp_can_send_msg_buf_len: u8; - #[link_name = "g_mock_mcp_can_send_msg_buf_buf"] pub static mut g_mock_mcp_can_send_msg_buf_buf: *mut u8; - #[link_name = "g_mock_arduino_analog_read_return"] pub static mut g_mock_arduino_analog_read_return: isize; } +impl Arbitrary for oscc_brake_enable_s { + fn arbitrary(g: &mut G) -> oscc_brake_enable_s { + oscc_brake_enable_s { + magic: [OSCC_MAGIC_BYTE_0 as u8, OSCC_MAGIC_BYTE_1 as u8], + reserved: [u8::arbitrary(g); 6], + } + } +} + +impl Arbitrary for oscc_brake_disable_s { + fn arbitrary(g: &mut G) -> oscc_brake_disable_s { + oscc_brake_disable_s { + magic: [OSCC_MAGIC_BYTE_0 as u8, OSCC_MAGIC_BYTE_1 as u8], + reserved: [u8::arbitrary(g); 6], + } + } +} + impl Arbitrary for oscc_brake_report_s { fn arbitrary(g: &mut G) -> oscc_brake_report_s { oscc_brake_report_s { @@ -37,7 +47,7 @@ impl Arbitrary for oscc_brake_report_s { enabled: u8::arbitrary(g), operator_override: u8::arbitrary(g), dtcs: u8::arbitrary(g), - reserved: [u8::arbitrary(g); 3] + reserved: [u8::arbitrary(g); 3], } } } @@ -47,8 +57,7 @@ impl Arbitrary for oscc_brake_command_s { oscc_brake_command_s { magic: [OSCC_MAGIC_BYTE_0 as u8, OSCC_MAGIC_BYTE_1 as u8], pedal_command: u16::arbitrary(g), - enable: u8::arbitrary(g), - reserved: [u8::arbitrary(g); 3] + reserved: [u8::arbitrary(g); 4], } } } @@ -60,7 +69,7 @@ impl Arbitrary for can_frame_s { id: u32::arbitrary(g), dlc: u8::arbitrary(g), timestamp: u32::arbitrary(g), - data: [u8::arbitrary(g); 8] + data: [u8::arbitrary(g); 8], } } } @@ -115,18 +124,40 @@ fn check_accel_pos_validity() { .quickcheck(prop_no_invalid_targets as fn(oscc_brake_command_s) -> TestResult) } -/// the throttle firmware should set the control state as disabled -/// upon reciept of a valid command throttle message telling it to disable -fn prop_process_disable_command(mut brake_command_msg: oscc_brake_command_s) -> TestResult { +/// the brake firmware should set the control state as enabled +/// upon reciept of a valid enable brake message telling it to enable +fn prop_process_enable_command(brake_enable_msg: oscc_brake_enable_s) -> TestResult { unsafe { - brake_command_msg.enable = 0u8; - g_brake_control_state.enabled = false; g_brake_control_state.operator_override = false; - g_mock_mcp_can_read_msg_buf_id = OSCC_BRAKE_COMMAND_CAN_ID; - g_mock_mcp_can_read_msg_buf_buf = std::mem::transmute(brake_command_msg); + g_mock_mcp_can_read_msg_buf_id = OSCC_BRAKE_ENABLE_CAN_ID; + g_mock_mcp_can_check_receive_return = CAN_MSGAVAIL as u8; + g_mock_mcp_can_read_msg_buf_buf = std::mem::transmute(brake_enable_msg); + + check_for_incoming_message(); + + TestResult::from_bool(g_brake_control_state.enabled == true) + } +} + +#[test] +fn check_process_enable_command() { + QuickCheck::new() + .tests(25) + .quickcheck(prop_process_enable_command as fn(oscc_brake_enable_s) -> TestResult) +} + +/// the brake firmware should set the control state as disabled +/// upon reciept of a valid disable brake message telling it to disable +fn prop_process_disable_command(brake_disable_msg: oscc_brake_disable_s) -> TestResult { + unsafe { + g_brake_control_state.enabled = true; + g_brake_control_state.operator_override = false; + + g_mock_mcp_can_read_msg_buf_id = OSCC_BRAKE_DISABLE_CAN_ID; g_mock_mcp_can_check_receive_return = CAN_MSGAVAIL as u8; + g_mock_mcp_can_read_msg_buf_buf = std::mem::transmute(brake_disable_msg); check_for_incoming_message(); @@ -137,6 +168,6 @@ fn prop_process_disable_command(mut brake_command_msg: oscc_brake_command_s) -> #[test] fn check_process_disable_command() { QuickCheck::new() - .tests(1000) - .quickcheck(prop_process_disable_command as fn(oscc_brake_command_s) -> TestResult) + .tests(25) + .quickcheck(prop_process_disable_command as fn(oscc_brake_disable_s) -> TestResult) } diff --git a/firmware/brake/utils/CMakeLists.txt b/firmware/brake/kia_soul_petrol/utils/CMakeLists.txt similarity index 100% rename from firmware/brake/utils/CMakeLists.txt rename to firmware/brake/kia_soul_petrol/utils/CMakeLists.txt diff --git a/firmware/brake/utils/release_pressure/CMakeLists.txt b/firmware/brake/kia_soul_petrol/utils/release_pressure/CMakeLists.txt similarity index 100% rename from firmware/brake/utils/release_pressure/CMakeLists.txt rename to firmware/brake/kia_soul_petrol/utils/release_pressure/CMakeLists.txt diff --git a/firmware/brake/utils/release_pressure/src/release_pressure.ino b/firmware/brake/kia_soul_petrol/utils/release_pressure/src/release_pressure.ino similarity index 100% rename from firmware/brake/utils/release_pressure/src/release_pressure.ino rename to firmware/brake/kia_soul_petrol/utils/release_pressure/src/release_pressure.ino diff --git a/firmware/brake/utils/serial_actuator/CMakeLists.txt b/firmware/brake/kia_soul_petrol/utils/serial_actuator/CMakeLists.txt similarity index 100% rename from firmware/brake/utils/serial_actuator/CMakeLists.txt rename to firmware/brake/kia_soul_petrol/utils/serial_actuator/CMakeLists.txt diff --git a/firmware/brake/utils/serial_actuator/src/serial_actuator.cpp b/firmware/brake/kia_soul_petrol/utils/serial_actuator/src/serial_actuator.cpp similarity index 100% rename from firmware/brake/utils/serial_actuator/src/serial_actuator.cpp rename to firmware/brake/kia_soul_petrol/utils/serial_actuator/src/serial_actuator.cpp diff --git a/firmware/can_gateway/include/communications.h b/firmware/can_gateway/include/communications.h index af8a4758..69da2fe4 100644 --- a/firmware/can_gateway/include/communications.h +++ b/firmware/can_gateway/include/communications.h @@ -5,8 +5,8 @@ */ -#ifndef _OSCC_KIA_SOUL_CAN_GATEWAY_COMMUNICATIONS_H_ -#define _OSCC_KIA_SOUL_CAN_GATEWAY_COMMUNICATIONS_H_ +#ifndef _OSCC_CAN_GATEWAY_COMMUNICATIONS_H_ +#define _OSCC_CAN_GATEWAY_COMMUNICATIONS_H_ #include "globals.h" @@ -26,4 +26,4 @@ void republish_obd_frames_to_control_can_bus( void ); -#endif /* _OSCC_KIA_SOUL_CAN_GATEWAY_COMMUNICATIONS_H_ */ +#endif /* _OSCC_CAN_GATEWAY_COMMUNICATIONS_H_ */ diff --git a/firmware/can_gateway/include/globals.h b/firmware/can_gateway/include/globals.h index 0de512d5..21f0c159 100644 --- a/firmware/can_gateway/include/globals.h +++ b/firmware/can_gateway/include/globals.h @@ -5,8 +5,8 @@ */ -#ifndef _OSCC_KIA_SOUL_CAN_GATEWAY_GLOBALS_H_ -#define _OSCC_KIA_SOUL_CAN_GATEWAY_GLOBALS_H_ +#ifndef _OSCC_CAN_GATEWAY_GLOBALS_H_ +#define _OSCC_CAN_GATEWAY_GLOBALS_H_ #include "mcp_can.h" @@ -38,4 +38,4 @@ #endif -#endif /* _OSCC_KIA_SOUL_CAN_GATEWAY_GLOBALS_H_ */ +#endif /* _OSCC_CAN_GATEWAY_GLOBALS_H_ */ diff --git a/firmware/can_gateway/include/init.h b/firmware/can_gateway/include/init.h index 82686bcd..231c1c3b 100644 --- a/firmware/can_gateway/include/init.h +++ b/firmware/can_gateway/include/init.h @@ -5,8 +5,8 @@ */ -#ifndef _OSCC_KIA_SOUL_CAN_GATEWAY_INIT_H_ -#define _OSCC_KIA_SOUL_CAN_GATEWAY_INIT_H_ +#ifndef _OSCC_CAN_GATEWAY_INIT_H_ +#define _OSCC_CAN_GATEWAY_INIT_H_ // **************************************************************************** @@ -22,4 +22,4 @@ void init_communication_interfaces( void ); -#endif /* _OSCC_KIA_SOUL_CAN_GATEWAY_INIT_H_ */ +#endif /* _OSCC_CAN_GATEWAY_INIT_H_ */ diff --git a/firmware/can_gateway/src/communications.cpp b/firmware/can_gateway/src/communications.cpp index d1938028..a7fcfbb7 100644 --- a/firmware/can_gateway/src/communications.cpp +++ b/firmware/can_gateway/src/communications.cpp @@ -4,13 +4,12 @@ */ +#include "communications.h" +#include "globals.h" #include "mcp_can.h" #include "oscc_can.h" #include "vehicles.h" -#include "globals.h" -#include "communications.h" - void republish_obd_frames_to_control_can_bus( void ) { diff --git a/firmware/can_gateway/src/init.cpp b/firmware/can_gateway/src/init.cpp index d7374b5d..f8182239 100644 --- a/firmware/can_gateway/src/init.cpp +++ b/firmware/can_gateway/src/init.cpp @@ -4,12 +4,11 @@ */ -#include "oscc_serial.h" -#include "oscc_can.h" #include "debug.h" - #include "globals.h" #include "init.h" +#include "oscc_can.h" +#include "oscc_serial.h" void init_communication_interfaces( void ) diff --git a/firmware/can_gateway/src/main.cpp b/firmware/can_gateway/src/main.cpp index c45f85bc..70b5bfd8 100644 --- a/firmware/can_gateway/src/main.cpp +++ b/firmware/can_gateway/src/main.cpp @@ -5,11 +5,11 @@ #include + #include "arduino_init.h" +#include "communications.h" #include "debug.h" - #include "init.h" -#include "communications.h" int main( void ) diff --git a/firmware/common/libs/can/oscc_can.cpp b/firmware/common/libs/can/oscc_can.cpp index f3986870..749e4cb4 100644 --- a/firmware/common/libs/can/oscc_can.cpp +++ b/firmware/common/libs/can/oscc_can.cpp @@ -1,8 +1,13 @@ +/** + * @file oscc_can.cpp + * + */ + + #include -#include "mcp_can.h" #include "debug.h" - +#include "mcp_can.h" #include "oscc_can.h" @@ -24,19 +29,19 @@ can_status_t check_for_rx_frame( MCP_CAN &can, can_frame_s * const frame ) if( frame != NULL ) { + memset( frame, 0, sizeof(*frame) ); + cli(); - if( can.checkReceive( ) == CAN_MSGAVAIL ) - { - memset( frame, 0, sizeof(*frame) ); + int got_message = can.readMsgBufID( + ( uint32_t* ) &frame->id, + ( uint8_t* ) &frame->dlc, + ( uint8_t* ) frame->data ); + if( got_message == CAN_OK ) + { frame->timestamp = millis( ); - can.readMsgBufID( - ( uint32_t* ) &frame->id, - ( uint8_t* ) &frame->dlc, - ( uint8_t* ) frame->data ); - ret = CAN_RX_FRAME_AVAILABLE; } else diff --git a/firmware/common/libs/can/oscc_can.h b/firmware/common/libs/can/oscc_can.h index 7aa3a033..03d2987c 100644 --- a/firmware/common/libs/can/oscc_can.h +++ b/firmware/common/libs/can/oscc_can.h @@ -10,6 +10,7 @@ #include + #include "mcp_can.h" diff --git a/firmware/common/libs/dac/oscc_dac.cpp b/firmware/common/libs/dac/oscc_dac.cpp index 8a35955a..2b7edceb 100644 --- a/firmware/common/libs/dac/oscc_dac.cpp +++ b/firmware/common/libs/dac/oscc_dac.cpp @@ -1,3 +1,9 @@ +/** + * @file oscc_dac.cpp + * + */ + + #include #include "oscc_dac.h" diff --git a/firmware/common/libs/dac/oscc_dac.h b/firmware/common/libs/dac/oscc_dac.h index 5b3dd071..94f2d224 100644 --- a/firmware/common/libs/dac/oscc_dac.h +++ b/firmware/common/libs/dac/oscc_dac.h @@ -1,6 +1,6 @@ /** - * @file helper.h - * @brief Helper functions. + * @file oscc_dac.h + * @brief OSCC DAC interface. * */ @@ -11,6 +11,7 @@ #include "DAC_MCP49xx.h" + /* * @brief Number of bits to shift to go from a 10-bit value to a 12-bit value. * diff --git a/firmware/common/libs/pid/tests/property/build.rs b/firmware/common/libs/pid/tests/property/build.rs index 2bba12ec..53cbab06 100644 --- a/firmware/common/libs/pid/tests/property/build.rs +++ b/firmware/common/libs/pid/tests/property/build.rs @@ -9,7 +9,6 @@ fn main() { .flag("-w") .file("../../oscc_pid.cpp") .cpp(true) - .compiler("/usr/bin/g++") .compile("libpid_test.a"); let out_dir = env::var("OUT_DIR").unwrap(); diff --git a/firmware/common/libs/serial/oscc_serial.cpp b/firmware/common/libs/serial/oscc_serial.cpp index 4e7beff6..54d395b2 100644 --- a/firmware/common/libs/serial/oscc_serial.cpp +++ b/firmware/common/libs/serial/oscc_serial.cpp @@ -1,10 +1,11 @@ /** - * @file serial.h + * @file oscc_serial.cpp * */ #include + #include "debug.h" #include "oscc_serial.h" diff --git a/firmware/common/libs/serial/oscc_serial.h b/firmware/common/libs/serial/oscc_serial.h index 2e388cfd..287ac9ed 100644 --- a/firmware/common/libs/serial/oscc_serial.h +++ b/firmware/common/libs/serial/oscc_serial.h @@ -1,5 +1,5 @@ /** - * @file serial.h + * @file oscc_serial.h * @brief Serial interface. * */ diff --git a/firmware/common/libs/timer/oscc_timer.cpp b/firmware/common/libs/timer/oscc_timer.cpp index 4f0479ad..4efc6325 100644 --- a/firmware/common/libs/timer/oscc_timer.cpp +++ b/firmware/common/libs/timer/oscc_timer.cpp @@ -4,7 +4,8 @@ */ -#include "Arduino.h" +#include + #include "oscc_timer.h" diff --git a/firmware/common/testing/mocks/Arduino_mock.cpp b/firmware/common/testing/mocks/Arduino_mock.cpp index e4fc4ba0..86aec6f9 100644 --- a/firmware/common/testing/mocks/Arduino_mock.cpp +++ b/firmware/common/testing/mocks/Arduino_mock.cpp @@ -7,9 +7,10 @@ unsigned long g_mock_arduino_millis_return; unsigned long g_mock_arduino_micros_return; -uint8_t g_mock_arduino_digital_write_pin; -uint8_t g_mock_arduino_digital_write_val; -int g_mock_arduino_analog_read_return; +uint8_t g_mock_arduino_digital_write_pins[100]; +uint8_t g_mock_arduino_digital_write_val[100]; +int g_mock_arduino_digital_write_count; +int g_mock_arduino_analog_read_return[100]; uint8_t g_mock_arduino_analog_write_pins[100]; int g_mock_arduino_analog_write_val[100]; int g_mock_arduino_analog_write_count; @@ -33,13 +34,17 @@ void pinMode(uint8_t, uint8_t) void digitalWrite(uint8_t pin, uint8_t val) { - g_mock_arduino_digital_write_pin = pin; - g_mock_arduino_digital_write_val = val; + g_mock_arduino_digital_write_pins[g_mock_arduino_digital_write_count] = pin; + g_mock_arduino_digital_write_val[g_mock_arduino_digital_write_count] = val; + + // need to keep track of successive calls to digitalWrite to be able to check + // all of their respective values + ++g_mock_arduino_digital_write_count; } int analogRead(uint8_t pin) { - return g_mock_arduino_analog_read_return; + return g_mock_arduino_analog_read_return[pin]; } void analogWrite(uint8_t pin, int val) diff --git a/firmware/common/testing/mocks/mcp_can.h b/firmware/common/testing/mocks/mcp_can.h index 856f12eb..592aa312 100644 --- a/firmware/common/testing/mocks/mcp_can.h +++ b/firmware/common/testing/mocks/mcp_can.h @@ -22,7 +22,6 @@ class MCP_CAN uint8_t begin(uint8_t speedset); uint8_t sendMsgBuf(uint32_t id, uint8_t ext, uint8_t len, uint8_t *buf); uint8_t readMsgBufID(uint32_t *ID, uint8_t *len, uint8_t *buf); - uint8_t checkReceive(void); }; #endif diff --git a/firmware/common/testing/mocks/mcp_can_mock.cpp b/firmware/common/testing/mocks/mcp_can_mock.cpp index 4d2433c5..de286da0 100644 --- a/firmware/common/testing/mocks/mcp_can_mock.cpp +++ b/firmware/common/testing/mocks/mcp_can_mock.cpp @@ -26,11 +26,6 @@ uint8_t MCP_CAN::begin(uint8_t speedset) return CAN_OK; } -uint8_t MCP_CAN::checkReceive(void) -{ - return g_mock_mcp_can_check_receive_return; -} - uint8_t MCP_CAN::sendMsgBuf(uint32_t id, uint8_t ext, uint8_t len, uint8_t *buf) { g_mock_mcp_can_send_msg_buf_id = id; @@ -46,6 +41,12 @@ uint8_t MCP_CAN::sendMsgBuf(uint32_t id, uint8_t ext, uint8_t len, uint8_t *buf) uint8_t MCP_CAN::readMsgBufID(uint32_t *ID, uint8_t *len, uint8_t *buf) { + if( g_mock_mcp_can_check_receive_return != CAN_MSGAVAIL) + { + *len = 0; + return CAN_NOMSG; + } + *ID = g_mock_mcp_can_read_msg_buf_id; *len = 8; diff --git a/firmware/steering/include/communications.h b/firmware/steering/include/communications.h index 14192aa9..78e5f6b9 100644 --- a/firmware/steering/include/communications.h +++ b/firmware/steering/include/communications.h @@ -5,8 +5,8 @@ */ -#ifndef _OSCC_KIA_SOUL_STEERING_COMMUNICATIONS_H_ -#define _OSCC_KIA_SOUL_STEERING_COMMUNICATIONS_H_ +#ifndef _OSCC_STEERING_COMMUNICATIONS_H_ +#define _OSCC_STEERING_COMMUNICATIONS_H_ // **************************************************************************** @@ -62,4 +62,4 @@ void check_for_controller_command_timeout( void ); void check_for_incoming_message( void ); -#endif /* _OSCC_KIA_SOUL_STEERING_COMMUNICATIONS_H_ */ +#endif /* _OSCC_STEERING_COMMUNICATIONS_H_ */ diff --git a/firmware/steering/include/globals.h b/firmware/steering/include/globals.h index 2a9cc49b..04927c77 100644 --- a/firmware/steering/include/globals.h +++ b/firmware/steering/include/globals.h @@ -5,13 +5,12 @@ */ -#ifndef _KIA_SOUL_STEERING_GLOBALS_H_ -#define _KIA_SOUL_STEERING_GLOBALS_H_ +#ifndef _OSCC_STEERING_GLOBALS_H_ +#define _OSCC_STEERING_GLOBALS_H_ #include "DAC_MCP49xx.h" #include "mcp_can.h" - #include "steering_control.h" diff --git a/firmware/steering/include/init.h b/firmware/steering/include/init.h index 83be570a..509a466f 100644 --- a/firmware/steering/include/init.h +++ b/firmware/steering/include/init.h @@ -5,8 +5,8 @@ */ -#ifndef _OSCC_KIA_SOUL_STEERING_INIT_H_ -#define _OSCC_KIA_SOUL_STEERING_INIT_H_ +#ifndef _OSCC_STEERING_INIT_H_ +#define _OSCC_STEERING_INIT_H_ // **************************************************************************** diff --git a/firmware/steering/include/steering_control.h b/firmware/steering/include/steering_control.h index b01296e9..9035fae9 100644 --- a/firmware/steering/include/steering_control.h +++ b/firmware/steering/include/steering_control.h @@ -5,8 +5,8 @@ */ -#ifndef _OSCC_KIA_SOUL_STEERING_CONTROL_H_ -#define _OSCC_KIA_SOUL_STEERING_CONTROL_H_ +#ifndef _OSCC_STEERING_CONTROL_H_ +#define _OSCC_STEERING_CONTROL_H_ #include @@ -112,4 +112,4 @@ void enable_control( void ); void disable_control( void ); -#endif /* _OSCC_KIA_SOUL_STEERING_CONTROL_H_ */ +#endif /* _OSCC_STEERING_CONTROL_H_ */ diff --git a/firmware/steering/include/timers.h b/firmware/steering/include/timers.h index a1a118c9..f99ee377 100644 --- a/firmware/steering/include/timers.h +++ b/firmware/steering/include/timers.h @@ -5,8 +5,8 @@ */ -#ifndef _OSCC_KIA_SOUL_STEERING_TIMERS_H_ -#define _OSCC_KIA_SOUL_STEERING_TIMERS_H_ +#ifndef _OSCC_STEERING_TIMERS_H_ +#define _OSCC_STEERING_TIMERS_H_ // **************************************************************************** @@ -22,4 +22,4 @@ void start_timers( void ); -#endif /* _OSCC_KIA_SOUL_TH_OSCC_KIA_SOUL_STEERING_TIMERS_H_ROTTLE_TIMERS_H_ */ +#endif /* _OSCC_TH_OSCC_STEERING_TIMERS_H_ROTTLE_TIMERS_H_ */ diff --git a/firmware/steering/src/communications.cpp b/firmware/steering/src/communications.cpp index 6b2d81b9..546ba870 100644 --- a/firmware/steering/src/communications.cpp +++ b/firmware/steering/src/communications.cpp @@ -4,15 +4,16 @@ */ -#include "mcp_can.h" -#include "oscc_can.h" +#include + #include "can_protocols/fault_can_protocol.h" #include "can_protocols/steering_can_protocol.h" +#include "communications.h" #include "debug.h" - #include "globals.h" -#include "communications.h" +#include "mcp_can.h" #include "steering_control.h" +#include "oscc_can.h" static void process_rx_frame( @@ -52,6 +53,7 @@ void publish_fault_report( void ) fault_report.magic[0] = (uint8_t) OSCC_MAGIC_BYTE_0; fault_report.magic[1] = (uint8_t) OSCC_MAGIC_BYTE_1; fault_report.fault_origin_id = FAULT_ORIGIN_STEERING; + fault_report.dtcs = g_steering_control_state.dtcs; cli(); g_control_can.sendMsgBuf( @@ -99,7 +101,15 @@ static void process_rx_frame( if( (frame->data[0] == OSCC_MAGIC_BYTE_0) && (frame->data[1] == OSCC_MAGIC_BYTE_1) ) { - if ( frame->id == OSCC_STEERING_COMMAND_CAN_ID ) + if ( frame->id == OSCC_STEERING_ENABLE_CAN_ID ) + { + enable_control( ); + } + else if ( frame->id == OSCC_STEERING_DISABLE_CAN_ID ) + { + disable_control( ); + } + else if ( frame->id == OSCC_STEERING_COMMAND_CAN_ID ) { process_steering_command( frame->data ); } @@ -120,18 +130,9 @@ static void process_steering_command( const oscc_steering_command_s * const steering_command = (oscc_steering_command_s *) data; - if ( steering_command->enable == true ) - { - enable_control( ); - - update_steering( - steering_command->spoof_value_high, - steering_command->spoof_value_low ); - } - else - { - disable_control( ); - } + update_steering( + steering_command->spoof_value_high, + steering_command->spoof_value_low ); g_steering_command_timeout = false; } @@ -148,6 +149,9 @@ static void process_fault_report( disable_control( ); - DEBUG_PRINTLN( "Fault report received" ); + DEBUG_PRINT( "Fault report received from: " ); + DEBUG_PRINT( fault_report->fault_origin_id ); + DEBUG_PRINT( " DTCs: "); + DEBUG_PRINTLN( fault_report->dtcs ); } } diff --git a/firmware/steering/src/init.cpp b/firmware/steering/src/init.cpp index 43208982..500e0878 100644 --- a/firmware/steering/src/init.cpp +++ b/firmware/steering/src/init.cpp @@ -5,14 +5,14 @@ #include -#include "oscc_serial.h" -#include "oscc_can.h" + #include "can_protocols/steering_can_protocol.h" +#include "communications.h" #include "debug.h" - #include "globals.h" -#include "communications.h" #include "init.h" +#include "oscc_can.h" +#include "oscc_serial.h" void init_globals( void ) diff --git a/firmware/steering/src/main.cpp b/firmware/steering/src/main.cpp index e771bba8..fdadf06b 100644 --- a/firmware/steering/src/main.cpp +++ b/firmware/steering/src/main.cpp @@ -5,12 +5,11 @@ #include "arduino_init.h" +#include "communications.h" #include "debug.h" - #include "init.h" -#include "timers.h" -#include "communications.h" #include "steering_control.h" +#include "timers.h" int main( void ) @@ -31,6 +30,8 @@ int main( void ) { check_for_incoming_message( ); +#ifdef STEERING_OVERRIDE check_for_operator_override( ); +#endif } } diff --git a/firmware/steering/src/steering_control.cpp b/firmware/steering/src/steering_control.cpp index dc88e6d5..8690fce6 100644 --- a/firmware/steering/src/steering_control.cpp +++ b/firmware/steering/src/steering_control.cpp @@ -5,17 +5,17 @@ #include -#include #include -#include "debug.h" -#include "oscc_dac.h" -#include "can_protocols/steering_can_protocol.h" -#include "dtc.h" -#include "vehicles.h" +#include +#include "can_protocols/steering_can_protocol.h" #include "communications.h" -#include "steering_control.h" +#include "debug.h" +#include "dtc.h" #include "globals.h" +#include "oscc_dac.h" +#include "steering_control.h" +#include "vehicles.h" /* @@ -29,6 +29,14 @@ static void read_torque_sensor( steering_torque_s * value ); +static float exponential_moving_average( + const float alpha, + const float input, + const float average ); + + +static uint16_t filtered_diff = 0; + void check_for_operator_override( void ) { @@ -39,11 +47,28 @@ void check_for_operator_override( void ) read_torque_sensor( &torque ); - if ( (abs(torque.high) >= OVERRIDE_WHEEL_THRESHOLD_IN_DEGREES_PER_USEC) - || (abs(torque.low) >= OVERRIDE_WHEEL_THRESHOLD_IN_DEGREES_PER_USEC) ) + uint16_t unfiltered_diff = abs( ( int )torque.high - ( int )torque.low ); + + const float filter_alpha = 0.01; + + if ( filtered_diff == 0 ) + { + filtered_diff = unfiltered_diff; + } + + filtered_diff = exponential_moving_average( + filter_alpha, + unfiltered_diff, + filtered_diff); + + if( abs( filtered_diff ) > TORQUE_DIFFERENCE_OVERRIDE_THRESHOLD ) { disable_control( ); + DTC_SET( + g_steering_control_state.dtcs, + OSCC_STEERING_DTC_OPERATOR_OVERRIDE ); + publish_fault_report( ); g_steering_control_state.operator_override = true; @@ -52,6 +77,10 @@ void check_for_operator_override( void ) } else { + DTC_CLEAR( + g_steering_control_state.dtcs, + OSCC_STEERING_DTC_OPERATOR_OVERRIDE ); + g_steering_control_state.operator_override = false; } } @@ -79,12 +108,12 @@ void check_for_sensor_faults( void ) { disable_control( ); - publish_fault_report( ); - DTC_SET( g_steering_control_state.dtcs, OSCC_STEERING_DTC_INVALID_SENSOR_VAL ); + publish_fault_report( ); + DEBUG_PRINTLN( "Bad value read from torque sensor" ); } } @@ -109,14 +138,14 @@ void update_steering( uint16_t spoof_high = constrain( spoof_command_high, - STEERING_SPOOF_SIGNAL_MIN, - STEERING_SPOOF_SIGNAL_MAX ); + STEERING_SPOOF_HIGH_SIGNAL_RANGE_MIN, + STEERING_SPOOF_HIGH_SIGNAL_RANGE_MAX ); uint16_t spoof_low = constrain( spoof_command_low, - STEERING_SPOOF_SIGNAL_MIN, - STEERING_SPOOF_SIGNAL_MAX ); + STEERING_SPOOF_LOW_SIGNAL_RANGE_MIN, + STEERING_SPOOF_LOW_SIGNAL_RANGE_MAX ); cli(); g_dac.outputA( spoof_high ); @@ -142,6 +171,7 @@ void enable_control( void ) digitalWrite( PIN_SPOOF_ENABLE, HIGH ); sei(); + g_steering_command_timeout = false; g_steering_control_state.enabled = true; DEBUG_PRINTLN( "Control enabled" ); @@ -164,18 +194,29 @@ void disable_control( void ) digitalWrite( PIN_SPOOF_ENABLE, LOW ); sei(); + g_steering_command_timeout = false; g_steering_control_state.enabled = false; + filtered_diff = 0; + DEBUG_PRINTLN( "Control disabled" ); } } +static float exponential_moving_average( + const float alpha, + const float input, + const float average ) +{ + return ( (alpha * input) + ((1.0 - alpha) * average) ); +} + static void read_torque_sensor( steering_torque_s * value ) { cli(); - value->high = analogRead( PIN_TORQUE_SENSOR_HIGH ); - value->low = analogRead( PIN_TORQUE_SENSOR_LOW ); + value->high = analogRead( PIN_TORQUE_SENSOR_HIGH ) << 2; + value->low = analogRead( PIN_TORQUE_SENSOR_LOW ) << 2; sei(); } diff --git a/firmware/steering/src/timers.cpp b/firmware/steering/src/timers.cpp index 8a3b5434..d169791b 100644 --- a/firmware/steering/src/timers.cpp +++ b/firmware/steering/src/timers.cpp @@ -4,13 +4,14 @@ */ -#include "can_protocols/steering_can_protocol.h" -#include "oscc_timer.h" +#include -#include "timers.h" -#include "globals.h" +#include "can_protocols/steering_can_protocol.h" #include "communications.h" +#include "globals.h" +#include "oscc_timer.h" #include "steering_control.h" +#include "timers.h" /* diff --git a/firmware/steering/tests/features/checking_faults.feature b/firmware/steering/tests/features/checking_faults.feature index 2b3e817a..ef696630 100644 --- a/firmware/steering/tests/features/checking_faults.feature +++ b/firmware/steering/tests/features/checking_faults.feature @@ -1,6 +1,6 @@ # language: en -Feature: Checking for fauls +Feature: Checking for faults If the module encounters a fault condition, it should disable control and publish a fault report. diff --git a/firmware/steering/tests/features/receiving_messages.feature b/firmware/steering/tests/features/receiving_messages.feature index 6eca1487..8f567126 100644 --- a/firmware/steering/tests/features/receiving_messages.feature +++ b/firmware/steering/tests/features/receiving_messages.feature @@ -39,13 +39,11 @@ Feature: Receiving commands Examples: | high | low | - | 3031 | 868 | - | 3000 | 1000 | + | 3440 | 656 | | 2500 | 1500 | | 2000 | 2000 | | 1500 | 2500 | - | 1000 | 3000 | - | 868 | 3031 | + | 738 | 3358 | Scenario Outline: Spoof value sent from application outside valid range @@ -58,7 +56,7 @@ Feature: Receiving commands Examples: | high | low | high_clamped | low_clamped | - | 4000 | 0 | 3031 | 868 | - | 3500 | 500 | 3031 | 868 | - | 500 | 3500 | 868 | 3031 | - | 0 | 4000 | 868 | 3031 | + | 4000 | 0 | 3440 | 656 | + | 3500 | 500 | 3440 | 656 | + | 500 | 3500 | 738 | 3358 | + | 0 | 4000 | 738 | 3358 | diff --git a/firmware/steering/tests/features/step_definitions/checking_faults.cpp b/firmware/steering/tests/features/step_definitions/checking_faults.cpp index 811c6a61..2dc4867d 100644 --- a/firmware/steering/tests/features/step_definitions/checking_faults.cpp +++ b/firmware/steering/tests/features/step_definitions/checking_faults.cpp @@ -1,6 +1,7 @@ WHEN("^a sensor becomes temporarily disconnected$") { - g_mock_arduino_analog_read_return = 0; + g_mock_arduino_analog_read_return[0] = 0; + g_mock_arduino_analog_read_return[1] = 0; check_for_sensor_faults(); @@ -12,7 +13,8 @@ WHEN("^a sensor becomes temporarily disconnected$") WHEN("^a sensor becomes permanently disconnected$") { - g_mock_arduino_analog_read_return = 0; + g_mock_arduino_analog_read_return[0] = 0; + g_mock_arduino_analog_read_return[1] = 0; // must call function enough times to exceed the fault limit for( int i = 0; i < 100; ++i ) @@ -34,9 +36,15 @@ WHEN("^the operator applies (.*) to the steering wheel$") { REGEX_PARAM(int, steering_sensor_val); - g_mock_arduino_analog_read_return = steering_sensor_val; + g_mock_arduino_analog_read_return[0] = steering_sensor_val; + g_mock_arduino_analog_read_return[1] = 0; - check_for_operator_override(); + // need to call since newest read only contributes 1% for smoothing + // and the average will start at 0.0 for the tests + for( int i = 0; i < 200; ++i ) + { + check_for_operator_override(); + } } diff --git a/firmware/steering/tests/features/step_definitions/common.cpp b/firmware/steering/tests/features/step_definitions/common.cpp index eb49888c..09fcfada 100644 --- a/firmware/steering/tests/features/step_definitions/common.cpp +++ b/firmware/steering/tests/features/step_definitions/common.cpp @@ -16,10 +16,11 @@ using namespace cgreen; -extern uint8_t g_mock_arduino_digital_write_pin; -extern uint8_t g_mock_arduino_digital_write_val; +extern uint8_t g_mock_arduino_digital_write_pins[100]; +extern uint8_t g_mock_arduino_digital_write_val[100]; +extern int g_mock_arduino_digital_write_count; -extern int g_mock_arduino_analog_read_return; +extern int g_mock_arduino_analog_read_return[100]; extern uint8_t g_mock_mcp_can_check_receive_return; extern uint32_t g_mock_mcp_can_read_msg_buf_id; @@ -38,10 +39,12 @@ extern volatile steering_control_state_s g_steering_control_state; // return to known state before every scenario BEFORE() { - g_mock_arduino_digital_write_pin = UINT8_MAX; - g_mock_arduino_digital_write_val = UINT8_MAX; + g_mock_arduino_digital_write_count = 0; + memset(&g_mock_arduino_digital_write_pins, 0, sizeof(g_mock_arduino_digital_write_pins)); + memset(&g_mock_arduino_digital_write_val, 0, sizeof(g_mock_arduino_digital_write_val)); - g_mock_arduino_analog_read_return = INT_MAX; + g_mock_arduino_analog_read_return[0] = INT_MAX; + g_mock_arduino_analog_read_return[1] = INT_MAX; g_mock_mcp_can_check_receive_return = UINT8_MAX; g_mock_mcp_can_read_msg_buf_id = UINT32_MAX; @@ -76,7 +79,8 @@ GIVEN("^the torque sensors have a reading of (.*)$") { REGEX_PARAM(int, sensor_val); - g_mock_arduino_analog_read_return = sensor_val; + g_mock_arduino_analog_read_return[0] = sensor_val; + g_mock_arduino_analog_read_return[1] = sensor_val; } @@ -84,7 +88,8 @@ GIVEN("^the operator has applied (.*) to the steering wheel$") { REGEX_PARAM(int, steering_sensor_val); - g_mock_arduino_analog_read_return = steering_sensor_val; + g_mock_arduino_analog_read_return[0] = steering_sensor_val; + g_mock_arduino_analog_read_return[1] = steering_sensor_val; check_for_operator_override(); } @@ -97,11 +102,11 @@ THEN("^control should be enabled$") is_equal_to(1)); assert_that( - g_mock_arduino_digital_write_pin, + g_mock_arduino_digital_write_pins[0], is_equal_to(PIN_SPOOF_ENABLE)); assert_that( - g_mock_arduino_digital_write_val, + g_mock_arduino_digital_write_val[0], is_equal_to(HIGH)); } @@ -113,11 +118,11 @@ THEN("^control should be disabled$") is_equal_to(0)); assert_that( - g_mock_arduino_digital_write_pin, + g_mock_arduino_digital_write_pins[0], is_equal_to(PIN_SPOOF_ENABLE)); assert_that( - g_mock_arduino_digital_write_val, + g_mock_arduino_digital_write_val[0], is_equal_to(LOW)); } diff --git a/firmware/steering/tests/features/step_definitions/receiving_messages.cpp b/firmware/steering/tests/features/step_definitions/receiving_messages.cpp index e4b6bcf5..ece3ee4d 100644 --- a/firmware/steering/tests/features/step_definitions/receiving_messages.cpp +++ b/firmware/steering/tests/features/step_definitions/receiving_messages.cpp @@ -1,14 +1,13 @@ WHEN("^an enable steering command is received$") { + g_mock_mcp_can_read_msg_buf_id = OSCC_STEERING_ENABLE_CAN_ID; g_mock_mcp_can_check_receive_return = CAN_MSGAVAIL; - g_mock_mcp_can_read_msg_buf_id = OSCC_STEERING_COMMAND_CAN_ID; - oscc_steering_command_s * steering_command = - (oscc_steering_command_s *) g_mock_mcp_can_read_msg_buf_buf; + oscc_steering_enable_s * steering_enable = + (oscc_steering_enable_s *) g_mock_mcp_can_read_msg_buf_buf; - steering_command->magic[0] = OSCC_MAGIC_BYTE_0; - steering_command->magic[1] = OSCC_MAGIC_BYTE_1; - steering_command->enable = 1; + steering_enable->magic[0] = OSCC_MAGIC_BYTE_0; + steering_enable->magic[1] = OSCC_MAGIC_BYTE_1; check_for_incoming_message(); } @@ -16,15 +15,14 @@ WHEN("^an enable steering command is received$") WHEN("^a disable steering command is received$") { + g_mock_mcp_can_read_msg_buf_id = OSCC_STEERING_DISABLE_CAN_ID; g_mock_mcp_can_check_receive_return = CAN_MSGAVAIL; - g_mock_mcp_can_read_msg_buf_id = OSCC_STEERING_COMMAND_CAN_ID; - oscc_steering_command_s * steering_command = - (oscc_steering_command_s *) g_mock_mcp_can_read_msg_buf_buf; + oscc_steering_disable_s * steering_disable = + (oscc_steering_disable_s *) g_mock_mcp_can_read_msg_buf_buf; - steering_command->magic[0] = OSCC_MAGIC_BYTE_0; - steering_command->magic[1] = OSCC_MAGIC_BYTE_1; - steering_command->enable = 0; + steering_disable->magic[0] = OSCC_MAGIC_BYTE_0; + steering_disable->magic[1] = OSCC_MAGIC_BYTE_1; check_for_incoming_message(); } @@ -59,7 +57,6 @@ WHEN("^a command is received with spoof values (.*) and (.*)$") steering_command->magic[0] = OSCC_MAGIC_BYTE_0; steering_command->magic[1] = OSCC_MAGIC_BYTE_1; - steering_command->enable = 1; steering_command->spoof_value_high = high; steering_command->spoof_value_low = low; diff --git a/firmware/steering/tests/property/build.rs b/firmware/steering/tests/property/build.rs index 9ef7ddb8..aab81c39 100644 --- a/firmware/steering/tests/property/build.rs +++ b/firmware/steering/tests/property/build.rs @@ -5,7 +5,7 @@ use std::env; use std::path::Path; fn main() { - gcc::Config::new() + gcc::Build::new() .flag("-w") .define("KIA_SOUL", Some("ON")) .include("include") @@ -23,6 +23,7 @@ fn main() { .file("../../src/communications.cpp") .file("../../src/steering_control.cpp") .file("../../src/globals.cpp") + .cpp(true) .compile("libsteering_test.a"); let out_dir = env::var("OUT_DIR").unwrap(); @@ -42,17 +43,24 @@ fn main() { .whitelisted_function("check_for_operator_override") .whitelisted_var("OSCC_MAGIC_BYTE_0") .whitelisted_var("OSCC_MAGIC_BYTE_1") + .whitelisted_var("OSCC_STEERING_ENABLE_CAN_ID") + .whitelisted_var("OSCC_STEERING_DISABLE_CAN_ID") .whitelisted_var("OSCC_STEERING_REPORT_CAN_ID") .whitelisted_var("OSCC_STEERING_REPORT_CAN_DLC") .whitelisted_var("OSCC_STEERING_COMMAND_CAN_ID") .whitelisted_var("OSCC_STEERING_COMMAND_CAN_DLC") .whitelisted_var("OSCC_FAULT_REPORT_CAN_ID") - .whitelisted_var("OSCC_STEERING_REPORT_PUBLISH_INTERVAL_IN_MSEC") - .whitelisted_var("OVERRIDE_WHEEL_THRESHOLD_IN_DEGREES_PER_USEC") - .whitelisted_var("STEERING_SPOOF_SIGNAL_MIN") - .whitelisted_var("STEERING_SPOOF_SIGNAL_MAX") + .whitelisted_var("PIN_TORQUE_SENSOR_HIGH") + .whitelisted_var("PIN_TORQUE_SENSOR_LOW") + .whitelisted_var("TORQUE_DIFFERENCE_OVERRIDE_THRESHOLD") + .whitelisted_var("STEERING_SPOOF_LOW_SIGNAL_RANGE_MIN") + .whitelisted_var("STEERING_SPOOF_LOW_SIGNAL_RANGE_MAX") + .whitelisted_var("STEERING_SPOOF_HIGH_SIGNAL_RANGE_MIN") + .whitelisted_var("STEERING_SPOOF_HIGH_SIGNAL_RANGE_MAX") .whitelisted_var("CAN_STANDARD") .whitelisted_var("CAN_MSGAVAIL") + .whitelisted_type("oscc_steering_enable_s") + .whitelisted_type("oscc_steering_disable_s") .whitelisted_type("oscc_steering_report_s") .whitelisted_type("oscc_steering_command_s") .whitelisted_type("can_frame_s") diff --git a/firmware/steering/tests/property/src/tests.rs b/firmware/steering/tests/property/src/tests.rs index 373a72e3..095d693d 100644 --- a/firmware/steering/tests/property/src/tests.rs +++ b/firmware/steering/tests/property/src/tests.rs @@ -13,30 +13,37 @@ use quickcheck::{QuickCheck, TestResult, Arbitrary, Gen, StdGen}; use rand::Rng; extern "C" { - #[link_name = "g_mock_mcp_can_check_receive_return"] pub static mut g_mock_mcp_can_check_receive_return: u8; - #[link_name = "g_mock_mcp_can_read_msg_buf_id"] pub static mut g_mock_mcp_can_read_msg_buf_id: u32; - #[link_name = "g_mock_mcp_can_read_msg_buf_buf"] pub static mut g_mock_mcp_can_read_msg_buf_buf: [u8; 8usize]; - #[link_name = "g_mock_mcp_can_send_msg_buf_id"] pub static mut g_mock_mcp_can_send_msg_buf_id: u32; - #[link_name = "g_mock_mcp_can_send_msg_buf_ext"] pub static mut g_mock_mcp_can_send_msg_buf_ext: u8; - #[link_name = "g_mock_mcp_can_send_msg_buf_len"] pub static mut g_mock_mcp_can_send_msg_buf_len: u8; - #[link_name = "g_mock_mcp_can_send_msg_buf_buf"] pub static mut g_mock_mcp_can_send_msg_buf_buf: *mut u8; - #[link_name = "g_mock_arduino_analog_read_return"] - pub static mut g_mock_arduino_analog_read_return: isize; - #[link_name = "g_mock_dac_output_a"] + pub static mut g_mock_arduino_analog_read_return: [isize; 100usize]; pub static mut g_mock_dac_output_a: u16; - #[link_name = "g_mock_dac_output_b"] pub static mut g_mock_dac_output_b: u16; - #[link_name = "g_steering_control_state"] pub static mut g_steering_control_state: steering_control_state_s; } +impl Arbitrary for oscc_steering_enable_s { + fn arbitrary(g: &mut G) -> oscc_steering_enable_s { + oscc_steering_enable_s { + magic: [OSCC_MAGIC_BYTE_0 as u8, OSCC_MAGIC_BYTE_1 as u8], + reserved: [u8::arbitrary(g); 6], + } + } +} + +impl Arbitrary for oscc_steering_disable_s { + fn arbitrary(g: &mut G) -> oscc_steering_disable_s { + oscc_steering_disable_s { + magic: [OSCC_MAGIC_BYTE_0 as u8, OSCC_MAGIC_BYTE_1 as u8], + reserved: [u8::arbitrary(g); 6], + } + } +} + impl Arbitrary for oscc_steering_report_s { fn arbitrary(g: &mut G) -> oscc_steering_report_s { oscc_steering_report_s { @@ -44,7 +51,7 @@ impl Arbitrary for oscc_steering_report_s { enabled: u8::arbitrary(g), operator_override: u8::arbitrary(g), dtcs: u8::arbitrary(g), - reserved: [u8::arbitrary(g); 3] + reserved: [u8::arbitrary(g); 3], } } } @@ -55,8 +62,7 @@ impl Arbitrary for oscc_steering_command_s { magic: [OSCC_MAGIC_BYTE_0 as u8, OSCC_MAGIC_BYTE_1 as u8], spoof_value_low: u16::arbitrary(g), spoof_value_high: u16::arbitrary(g), - enable: u8::arbitrary(g), - reserved: u8::arbitrary(g) + reserved: [u8::arbitrary(g); 2], } } } @@ -67,7 +73,7 @@ impl Arbitrary for can_frame_s { id: u32::arbitrary(g), dlc: u8::arbitrary(g), timestamp: u32::arbitrary(g), - data: [u8::arbitrary(g); 8] + data: [u8::arbitrary(g); 8], } } } @@ -76,10 +82,12 @@ impl Arbitrary for can_frame_s { /// that are not steering or fault commands /// this means that none of the steering control state would /// change, nor would it output any values onto the DAC. -fn prop_only_process_valid_messages(rx_can_msg: can_frame_s, enabled: bool, operator_override: bool, dtcs: u8) -> TestResult { - if rx_can_msg.id == OSCC_STEERING_COMMAND_CAN_ID || - rx_can_msg.id == OSCC_FAULT_REPORT_CAN_ID - { +fn prop_only_process_valid_messages(rx_can_msg: can_frame_s, + enabled: bool, + operator_override: bool, + dtcs: u8) + -> TestResult { + if rx_can_msg.id == OSCC_STEERING_COMMAND_CAN_ID || rx_can_msg.id == OSCC_FAULT_REPORT_CAN_ID { return TestResult::discard(); } unsafe { @@ -95,8 +103,7 @@ fn prop_only_process_valid_messages(rx_can_msg: can_frame_s, enabled: bool, oper check_for_incoming_message(); - TestResult::from_bool(g_steering_control_state.enabled == - enabled && + TestResult::from_bool(g_steering_control_state.enabled == enabled && g_steering_control_state.operator_override == operator_override && g_steering_control_state.dtcs == dtcs && g_mock_dac_output_a == dac_a && @@ -109,21 +116,20 @@ fn check_message_type_validity() { QuickCheck::new() .tests(1000) .gen(StdGen::new(rand::thread_rng(), u32::max_value() as usize)) - .quickcheck(prop_only_process_valid_messages as fn(can_frame_s, bool, bool, u8) -> TestResult) + .quickcheck(prop_only_process_valid_messages as + fn(can_frame_s, bool, bool, u8) -> TestResult) } /// the steering firmware should set the control state as enabled -/// upon reciept of a valid command steering message telling it to enable -fn prop_process_enable_command(mut steering_command_msg: oscc_steering_command_s) -> TestResult { +/// upon reciept of a valid enable steering message telling it to enable +fn prop_process_enable_command(steering_enable_msg: oscc_steering_enable_s) -> TestResult { unsafe { - steering_command_msg.enable = 1u8; - g_steering_control_state.enabled = false; g_steering_control_state.operator_override = false; - g_mock_mcp_can_read_msg_buf_id = OSCC_STEERING_COMMAND_CAN_ID; + g_mock_mcp_can_read_msg_buf_id = OSCC_STEERING_ENABLE_CAN_ID; g_mock_mcp_can_check_receive_return = CAN_MSGAVAIL as u8; - g_mock_mcp_can_read_msg_buf_buf = std::mem::transmute(steering_command_msg); + g_mock_mcp_can_read_msg_buf_buf = std::mem::transmute(steering_enable_msg); check_for_incoming_message(); @@ -135,18 +141,19 @@ fn prop_process_enable_command(mut steering_command_msg: oscc_steering_command_s fn check_process_enable_command() { QuickCheck::new() .tests(1000) - .quickcheck(prop_process_enable_command as fn(oscc_steering_command_s) -> TestResult) + .quickcheck(prop_process_enable_command as fn(oscc_steering_enable_s) -> TestResult) } /// the steering firmware should set the control state as disabled -/// upon reciept of a valid command steering message telling it to disable -fn prop_process_disable_command(mut steering_command_msg: oscc_steering_command_s) -> TestResult { +/// upon reciept of a valid disable steering message telling it to disable +fn prop_process_disable_command(steering_disable_msg: oscc_steering_disable_s) -> TestResult { unsafe { - steering_command_msg.enable = 0u8; + g_steering_control_state.enabled = true; + g_steering_control_state.operator_override = false; - g_mock_mcp_can_read_msg_buf_id = OSCC_STEERING_COMMAND_CAN_ID; - g_mock_mcp_can_read_msg_buf_buf = std::mem::transmute(steering_command_msg); + g_mock_mcp_can_read_msg_buf_id = OSCC_STEERING_DISABLE_CAN_ID; g_mock_mcp_can_check_receive_return = CAN_MSGAVAIL as u8; + g_mock_mcp_can_read_msg_buf_buf = std::mem::transmute(steering_disable_msg); check_for_incoming_message(); @@ -158,15 +165,14 @@ fn prop_process_disable_command(mut steering_command_msg: oscc_steering_command_ fn check_process_disable_command() { QuickCheck::new() .tests(1000) - .quickcheck(prop_process_disable_command as fn(oscc_steering_command_s) -> TestResult) + .quickcheck(prop_process_disable_command as fn(oscc_steering_disable_s) -> TestResult) } /// the steering firmware should send requested spoof values /// upon recieving a steering command message fn prop_output_accurate_spoofs(mut steering_command_msg: oscc_steering_command_s) -> TestResult { - steering_command_msg.enable = 1u8; - steering_command_msg.spoof_value_low = rand::thread_rng().gen_range(STEERING_SPOOF_SIGNAL_MIN as u16, STEERING_SPOOF_SIGNAL_MAX as u16); - steering_command_msg.spoof_value_high = rand::thread_rng().gen_range(STEERING_SPOOF_SIGNAL_MIN as u16, STEERING_SPOOF_SIGNAL_MAX as u16); + steering_command_msg.spoof_value_low = rand::thread_rng().gen_range(STEERING_SPOOF_LOW_SIGNAL_RANGE_MIN as u16, STEERING_SPOOF_LOW_SIGNAL_RANGE_MAX as u16); + steering_command_msg.spoof_value_high = rand::thread_rng().gen_range(STEERING_SPOOF_HIGH_SIGNAL_RANGE_MIN as u16, STEERING_SPOOF_HIGH_SIGNAL_RANGE_MAX as u16); unsafe { g_steering_control_state.enabled = true; @@ -192,17 +198,16 @@ fn check_output_accurate_spoofs() { /// the steering firmware should constrain requested spoof values /// upon recieving a steering command message -fn prop_output_constrained_spoofs(mut steering_command_msg: oscc_steering_command_s) -> TestResult { - steering_command_msg.enable = 1u8; +fn prop_output_constrained_spoofs(steering_command_msg: oscc_steering_command_s) -> TestResult { unsafe { - if (steering_command_msg.spoof_value_low >= - STEERING_SPOOF_SIGNAL_MIN as u16 && + if (steering_command_msg.spoof_value_low >= + STEERING_SPOOF_LOW_SIGNAL_RANGE_MIN as u16 && steering_command_msg.spoof_value_low <= - STEERING_SPOOF_SIGNAL_MAX as u16) || - (steering_command_msg.spoof_value_high >= - STEERING_SPOOF_SIGNAL_MIN as u16 && + STEERING_SPOOF_LOW_SIGNAL_RANGE_MAX as u16) || + (steering_command_msg.spoof_value_high >= + STEERING_SPOOF_HIGH_SIGNAL_RANGE_MIN as u16 && steering_command_msg.spoof_value_high <= - STEERING_SPOOF_SIGNAL_MAX as u16) + STEERING_SPOOF_HIGH_SIGNAL_RANGE_MAX as u16) { return TestResult::discard(); } @@ -216,10 +221,10 @@ fn prop_output_constrained_spoofs(mut steering_command_msg: oscc_steering_comman check_for_incoming_message(); TestResult::from_bool( - g_mock_dac_output_a >= STEERING_SPOOF_SIGNAL_MIN as u16 && - g_mock_dac_output_a <= STEERING_SPOOF_SIGNAL_MAX as u16 && - g_mock_dac_output_b >= STEERING_SPOOF_SIGNAL_MIN as u16 && - g_mock_dac_output_b <= STEERING_SPOOF_SIGNAL_MAX as u16) + g_mock_dac_output_a >= STEERING_SPOOF_HIGH_SIGNAL_RANGE_MIN as u16 && + g_mock_dac_output_a <= STEERING_SPOOF_HIGH_SIGNAL_RANGE_MAX as u16 && + g_mock_dac_output_b >= STEERING_SPOOF_LOW_SIGNAL_RANGE_MIN as u16 && + g_mock_dac_output_b <= STEERING_SPOOF_LOW_SIGNAL_RANGE_MAX as u16) } } @@ -260,15 +265,16 @@ fn check_valid_can_frame() { // the steering firmware should be able to correctly and consistently // detect operator overrides, disable on reciept, and send a fault report -fn prop_check_operator_override(analog_read_spoof: u16) -> TestResult { +fn prop_check_operator_override(analog_read_spoof_high: i16, analog_read_spoof_low: i16) -> TestResult { unsafe { g_steering_control_state.enabled = true; g_steering_control_state.operator_override = false; - g_mock_arduino_analog_read_return = analog_read_spoof as isize; + g_mock_arduino_analog_read_return[0] = analog_read_spoof_high as isize; + g_mock_arduino_analog_read_return[1] = analog_read_spoof_low as isize; check_for_operator_override(); - if analog_read_spoof >= (OVERRIDE_WHEEL_THRESHOLD_IN_DEGREES_PER_USEC as u16) { + if (analog_read_spoof_high - analog_read_spoof_low) >= (TORQUE_DIFFERENCE_OVERRIDE_THRESHOLD as i16) { TestResult::from_bool(g_steering_control_state.operator_override == true && g_steering_control_state.enabled == false && g_mock_mcp_can_send_msg_buf_id == OSCC_FAULT_REPORT_CAN_ID) } else { @@ -281,8 +287,7 @@ fn prop_check_operator_override(analog_read_spoof: u16) -> TestResult { fn check_operator_override() { QuickCheck::new() .tests(1000) - .gen(StdGen::new(rand::thread_rng(), u16::max_value() as usize)) - .quickcheck(prop_check_operator_override as fn(u16) -> TestResult) + .quickcheck(prop_check_operator_override as fn(i16, i16) -> TestResult) } /// the steering firmware should set disable itself when it recieves a diff --git a/firmware/throttle/include/communications.h b/firmware/throttle/include/communications.h index b2964774..4fd150e8 100644 --- a/firmware/throttle/include/communications.h +++ b/firmware/throttle/include/communications.h @@ -5,8 +5,8 @@ */ -#ifndef _OSCC_KIA_SOUL_THROTTLE_COMMUNICATIONS_H_ -#define _OSCC_KIA_SOUL_THROTTLE_COMMUNICATIONS_H_ +#ifndef _OSCC_THROTTLE_COMMUNICATIONS_H_ +#define _OSCC_THROTTLE_COMMUNICATIONS_H_ // **************************************************************************** @@ -62,4 +62,4 @@ void check_for_controller_command_timeout( void ); void check_for_incoming_message( void ); -#endif /* _OSCC_KIA_SOUL_THROTTLE_COMMUNICATIONS_H_ */ +#endif /* _OSCC_THROTTLE_COMMUNICATIONS_H_ */ diff --git a/firmware/throttle/include/globals.h b/firmware/throttle/include/globals.h index 8e58ec03..1109a35c 100644 --- a/firmware/throttle/include/globals.h +++ b/firmware/throttle/include/globals.h @@ -5,13 +5,12 @@ */ -#ifndef _OSCC_KIA_SOUL_THROTTLE_GLOBALS_H_ -#define _OSCC_KIA_SOUL_THROTTLE_GLOBALS_H_ +#ifndef _OSCC_THROTTLE_GLOBALS_H_ +#define _OSCC_THROTTLE_GLOBALS_H_ #include "DAC_MCP49xx.h" #include "mcp_can.h" - #include "throttle_control.h" @@ -76,4 +75,4 @@ EXTERN volatile bool g_throttle_command_timeout; EXTERN volatile throttle_control_state_s g_throttle_control_state; -#endif /* _OSCC_KIA_SOUL_THROTTLE_GLOBALS_H_ */ +#endif /* _OSCC_THROTTLE_GLOBALS_H_ */ diff --git a/firmware/throttle/include/init.h b/firmware/throttle/include/init.h index 010934ca..f71af23c 100644 --- a/firmware/throttle/include/init.h +++ b/firmware/throttle/include/init.h @@ -5,8 +5,8 @@ */ -#ifndef _OSCC_KIA_SOUL_THROTTLE_INIT_H_ -#define _OSCC_KIA_SOUL_THROTTLE_INIT_H_ +#ifndef _OSCC_THROTTLE_INIT_H_ +#define _OSCC_THROTTLE_INIT_H_ // **************************************************************************** @@ -48,4 +48,4 @@ void init_devices( void ); void init_communication_interfaces( void ); -#endif /* _OSCC_KIA_SOUL_THROTTLE_INIT_H_ */ +#endif /* _OSCC_THROTTLE_INIT_H_ */ diff --git a/firmware/throttle/include/throttle_control.h b/firmware/throttle/include/throttle_control.h index 26d121f1..1fe9c3dc 100644 --- a/firmware/throttle/include/throttle_control.h +++ b/firmware/throttle/include/throttle_control.h @@ -5,8 +5,8 @@ */ -#ifndef _OSCC_KIA_SOUL_THROTTLE_CONTROL_H_ -#define _OSCC_KIA_SOUL_THROTTLE_CONTROL_H_ +#ifndef _OSCC_THROTTLE_CONTROL_H_ +#define _OSCC_THROTTLE_CONTROL_H_ #include @@ -112,4 +112,4 @@ void enable_control( void ); void disable_control( void ); -#endif /* _OSCC_KIA_SOUL_THROTTLE_CONTROL_H_ */ +#endif /* _OSCC_THROTTLE_CONTROL_H_ */ diff --git a/firmware/throttle/include/timers.h b/firmware/throttle/include/timers.h index cde065e2..cefc8cae 100644 --- a/firmware/throttle/include/timers.h +++ b/firmware/throttle/include/timers.h @@ -5,8 +5,8 @@ */ -#ifndef _OSCC_KIA_SOUL_THROTTLE_TIMERS_H_ -#define _OSCC_KIA_SOUL_THROTTLE_TIMERS_H_ +#ifndef _OSCC_THROTTLE_TIMERS_H_ +#define _OSCC_THROTTLE_TIMERS_H_ // **************************************************************************** @@ -22,4 +22,4 @@ void start_timers( void ); -#endif /* _OSCC_KIA_SOUL_THROTTLE_TIMERS_H_ */ +#endif /* _OSCC_THROTTLE_TIMERS_H_ */ diff --git a/firmware/throttle/src/communications.cpp b/firmware/throttle/src/communications.cpp index 27da7430..1f0d8645 100644 --- a/firmware/throttle/src/communications.cpp +++ b/firmware/throttle/src/communications.cpp @@ -4,14 +4,15 @@ */ -#include "mcp_can.h" -#include "oscc_can.h" +#include + #include "can_protocols/fault_can_protocol.h" #include "can_protocols/throttle_can_protocol.h" +#include "communications.h" #include "debug.h" - #include "globals.h" -#include "communications.h" +#include "mcp_can.h" +#include "oscc_can.h" #include "throttle_control.h" @@ -52,6 +53,7 @@ void publish_fault_report( void ) fault_report.magic[0] = (uint8_t) OSCC_MAGIC_BYTE_0; fault_report.magic[1] = (uint8_t) OSCC_MAGIC_BYTE_1; fault_report.fault_origin_id = FAULT_ORIGIN_THROTTLE; + fault_report.dtcs = g_throttle_control_state.dtcs; cli(); g_control_can.sendMsgBuf( @@ -73,7 +75,7 @@ void check_for_controller_command_timeout( void ) publish_fault_report( ); - DEBUG_PRINTLN( "Timeout waiting for controller command" ); + DEBUG_PRINTLN( "Timeout - controller command" ); } } } @@ -99,7 +101,15 @@ static void process_rx_frame( if( (frame->data[0] == OSCC_MAGIC_BYTE_0) && (frame->data[1] == OSCC_MAGIC_BYTE_1) ) { - if( frame->id == OSCC_THROTTLE_COMMAND_CAN_ID ) + if ( frame->id == OSCC_THROTTLE_ENABLE_CAN_ID ) + { + enable_control( ); + } + else if ( frame->id == OSCC_THROTTLE_DISABLE_CAN_ID ) + { + disable_control( ); + } + else if( frame->id == OSCC_THROTTLE_COMMAND_CAN_ID ) { process_throttle_command( frame->data ); } @@ -120,18 +130,9 @@ static void process_throttle_command( const oscc_throttle_command_s * const throttle_command = (oscc_throttle_command_s *) data; - if( throttle_command->enable == true ) - { - enable_control( ); - - update_throttle( - throttle_command->spoof_value_high, - throttle_command->spoof_value_low ); - } - else - { - disable_control( ); - } + update_throttle( + throttle_command->spoof_value_high, + throttle_command->spoof_value_low ); g_throttle_command_timeout = false; } @@ -148,6 +149,9 @@ static void process_fault_report( disable_control( ); - DEBUG_PRINTLN( "Fault report received" ); + DEBUG_PRINT( "Fault report received from: " ); + DEBUG_PRINT( fault_report->fault_origin_id ); + DEBUG_PRINT( " DTCs: "); + DEBUG_PRINTLN( fault_report->dtcs ); } } diff --git a/firmware/throttle/src/init.cpp b/firmware/throttle/src/init.cpp index 8ef62f29..f3091ee9 100644 --- a/firmware/throttle/src/init.cpp +++ b/firmware/throttle/src/init.cpp @@ -5,21 +5,21 @@ #include -#include "oscc_serial.h" -#include "oscc_can.h" + #include "can_protocols/throttle_can_protocol.h" +#include "communications.h" #include "debug.h" - #include "globals.h" -#include "communications.h" #include "init.h" +#include "oscc_can.h" +#include "oscc_serial.h" void init_globals( void ) { - g_throttle_control_state.enabled = false; - g_throttle_control_state.operator_override = false; - g_throttle_control_state.dtcs = 0; + g_throttle_control_state.enabled = false; + g_throttle_control_state.operator_override = false; + g_throttle_control_state.dtcs = 0; g_throttle_command_timeout = false; } diff --git a/firmware/throttle/src/main.cpp b/firmware/throttle/src/main.cpp index 3f7130e0..c399890a 100644 --- a/firmware/throttle/src/main.cpp +++ b/firmware/throttle/src/main.cpp @@ -5,13 +5,13 @@ #include "arduino_init.h" +#include "communications.h" #include "debug.h" - #include "init.h" #include "timers.h" -#include "communications.h" #include "throttle_control.h" + int main( void ) { init_arduino( ); diff --git a/firmware/throttle/src/throttle_control.cpp b/firmware/throttle/src/throttle_control.cpp index 348d0cf4..414543f8 100644 --- a/firmware/throttle/src/throttle_control.cpp +++ b/firmware/throttle/src/throttle_control.cpp @@ -6,15 +6,15 @@ #include #include -#include "debug.h" -#include "oscc_dac.h" -#include "can_protocols/throttle_can_protocol.h" -#include "dtc.h" -#include "vehicles.h" +#include "can_protocols/throttle_can_protocol.h" #include "communications.h" -#include "throttle_control.h" +#include "debug.h" +#include "dtc.h" #include "globals.h" +#include "oscc_dac.h" +#include "throttle_control.h" +#include "vehicles.h" /* @@ -45,6 +45,10 @@ void check_for_operator_override( void ) { disable_control( ); + DTC_SET( + g_throttle_control_state.dtcs, + OSCC_THROTTLE_DTC_OPERATOR_OVERRIDE ); + publish_fault_report( ); g_throttle_control_state.operator_override = true; @@ -53,6 +57,10 @@ void check_for_operator_override( void ) } else { + DTC_CLEAR( + g_throttle_control_state.dtcs, + OSCC_THROTTLE_DTC_OPERATOR_OVERRIDE ); + g_throttle_control_state.operator_override = false; } } @@ -80,12 +88,12 @@ void check_for_sensor_faults( void ) { disable_control( ); - publish_fault_report( ); - DTC_SET( g_throttle_control_state.dtcs, OSCC_THROTTLE_DTC_INVALID_SENSOR_VAL ); + publish_fault_report( ); + DEBUG_PRINTLN( "Bad value read from accelerator position sensor" ); } } @@ -143,6 +151,7 @@ void enable_control( void ) digitalWrite( PIN_SPOOF_ENABLE, HIGH ); sei(); + g_throttle_command_timeout = false; g_throttle_control_state.enabled = true; DEBUG_PRINTLN( "Control enabled" ); @@ -165,6 +174,7 @@ void disable_control( void ) digitalWrite( PIN_SPOOF_ENABLE, LOW ); sei(); + g_throttle_command_timeout = false; g_throttle_control_state.enabled = false; DEBUG_PRINTLN( "Control disabled" ); diff --git a/firmware/throttle/src/timers.cpp b/firmware/throttle/src/timers.cpp index 5b944608..a93cbaba 100644 --- a/firmware/throttle/src/timers.cpp +++ b/firmware/throttle/src/timers.cpp @@ -4,13 +4,14 @@ */ -#include "can_protocols/throttle_can_protocol.h" -#include "oscc_timer.h" +#include -#include "timers.h" -#include "globals.h" +#include "can_protocols/throttle_can_protocol.h" #include "communications.h" +#include "globals.h" +#include "oscc_timer.h" #include "throttle_control.h" +#include "timers.h" /* diff --git a/firmware/throttle/tests/features/receiving_messages.feature b/firmware/throttle/tests/features/receiving_messages.feature index 3d66cad5..91ed16f0 100644 --- a/firmware/throttle/tests/features/receiving_messages.feature +++ b/firmware/throttle/tests/features/receiving_messages.feature @@ -39,14 +39,14 @@ Feature: Receiving commands Examples: | high | low | - | 3500 | 0 | - | 3000 | 500 | - | 2500 | 1000 | - | 2000 | 1500 | - | 1500 | 1800 | - | 1000 | 1800 | - | 500 | 1800 | - | 0 | 1800 | + | 3358 | 328 | + | 3000 | 500 | + | 2500 | 1000 | + | 2000 | 1500 | + | 1500 | 1638 | + | 1000 | 1638 | + | 656 | 1638 | + | 573 | 1638 | Scenario Outline: Spoof value sent from application outside valid range @@ -59,7 +59,7 @@ Feature: Receiving commands Examples: | high | low | high_clamped | low_clamped | - | 4000 | 0 | 3500 | 0 | - | 3500 | 500 | 3500 | 500 | - | 500 | 3500 | 500 | 1800 | - | 0 | 4000 | 0 | 1800 | + | 4000 | 0 | 3358 | 245 | + | 3500 | 500 | 3358 | 500 | + | 580 | 3500 | 580 | 1638 | + | 500 | 4000 | 573 | 1638 | diff --git a/firmware/throttle/tests/features/step_definitions/checking_faults.cpp b/firmware/throttle/tests/features/step_definitions/checking_faults.cpp index 715bf723..0a09c09f 100644 --- a/firmware/throttle/tests/features/step_definitions/checking_faults.cpp +++ b/firmware/throttle/tests/features/step_definitions/checking_faults.cpp @@ -1,6 +1,7 @@ WHEN("^a sensor becomes temporarily disconnected$") { - g_mock_arduino_analog_read_return = 0; + g_mock_arduino_analog_read_return[0] = 0; + g_mock_arduino_analog_read_return[1] = 0; check_for_sensor_faults(); @@ -12,7 +13,8 @@ WHEN("^a sensor becomes temporarily disconnected$") WHEN("^a sensor becomes permanently disconnected$") { - g_mock_arduino_analog_read_return = 0; + g_mock_arduino_analog_read_return[0] = 0; + g_mock_arduino_analog_read_return[1] = 0; // must call function enough times to exceed the fault limit for( int i = 0; i < 100; ++i ) @@ -34,7 +36,8 @@ WHEN("^the operator applies (.*) to the accelerator$") { REGEX_PARAM(int, throttle_sensor_val); - g_mock_arduino_analog_read_return = throttle_sensor_val; + g_mock_arduino_analog_read_return[0] = throttle_sensor_val; + g_mock_arduino_analog_read_return[1] = throttle_sensor_val; check_for_operator_override(); } diff --git a/firmware/throttle/tests/features/step_definitions/common.cpp b/firmware/throttle/tests/features/step_definitions/common.cpp index fde4629f..a2636b08 100644 --- a/firmware/throttle/tests/features/step_definitions/common.cpp +++ b/firmware/throttle/tests/features/step_definitions/common.cpp @@ -16,10 +16,11 @@ using namespace cgreen; -extern uint8_t g_mock_arduino_digital_write_pin; -extern uint8_t g_mock_arduino_digital_write_val; +extern uint8_t g_mock_arduino_digital_write_pins[100]; +extern uint8_t g_mock_arduino_digital_write_val[100]; +extern int g_mock_arduino_digital_write_count; -extern int g_mock_arduino_analog_read_return; +extern int g_mock_arduino_analog_read_return[100]; extern uint8_t g_mock_mcp_can_check_receive_return; extern uint32_t g_mock_mcp_can_read_msg_buf_id; @@ -38,10 +39,12 @@ extern volatile throttle_control_state_s g_throttle_control_state; // return to known state before every scenario BEFORE() { - g_mock_arduino_digital_write_pin = UINT8_MAX; - g_mock_arduino_digital_write_val = UINT8_MAX; + g_mock_arduino_digital_write_count = 0; + memset(&g_mock_arduino_digital_write_pins, 0, sizeof(g_mock_arduino_digital_write_pins)); + memset(&g_mock_arduino_digital_write_val, 0, sizeof(g_mock_arduino_digital_write_val)); - g_mock_arduino_analog_read_return = INT_MAX; + g_mock_arduino_analog_read_return[0] = INT_MAX; + g_mock_arduino_analog_read_return[1] = INT_MAX; g_mock_mcp_can_check_receive_return = UINT8_MAX; g_mock_mcp_can_read_msg_buf_id = UINT32_MAX; @@ -76,7 +79,8 @@ GIVEN("^the accelerator position sensors have a reading of (.*)$") { REGEX_PARAM(int, sensor_val); - g_mock_arduino_analog_read_return = sensor_val; + g_mock_arduino_analog_read_return[0] = sensor_val; + g_mock_arduino_analog_read_return[1] = sensor_val; } @@ -85,7 +89,8 @@ GIVEN("^the operator has applied (.*) to the accelerator$") REGEX_PARAM(int, throttle_sensor_val); - g_mock_arduino_analog_read_return = throttle_sensor_val; + g_mock_arduino_analog_read_return[0] = throttle_sensor_val; + g_mock_arduino_analog_read_return[1] = throttle_sensor_val; check_for_operator_override(); } @@ -98,11 +103,11 @@ THEN("^control should be enabled$") is_equal_to(1)); assert_that( - g_mock_arduino_digital_write_pin, + g_mock_arduino_digital_write_pins[0], is_equal_to(PIN_SPOOF_ENABLE)); assert_that( - g_mock_arduino_digital_write_val, + g_mock_arduino_digital_write_val[0], is_equal_to(HIGH)); } @@ -114,11 +119,11 @@ THEN("^control should be disabled$") is_equal_to(0)); assert_that( - g_mock_arduino_digital_write_pin, + g_mock_arduino_digital_write_pins[0], is_equal_to(PIN_SPOOF_ENABLE)); assert_that( - g_mock_arduino_digital_write_val, + g_mock_arduino_digital_write_val[0], is_equal_to(LOW)); } diff --git a/firmware/throttle/tests/features/step_definitions/receiving_messages.cpp b/firmware/throttle/tests/features/step_definitions/receiving_messages.cpp index e9f3d22a..19058750 100644 --- a/firmware/throttle/tests/features/step_definitions/receiving_messages.cpp +++ b/firmware/throttle/tests/features/step_definitions/receiving_messages.cpp @@ -1,14 +1,13 @@ WHEN("^an enable throttle command is received$") { + g_mock_mcp_can_read_msg_buf_id = OSCC_THROTTLE_ENABLE_CAN_ID; g_mock_mcp_can_check_receive_return = CAN_MSGAVAIL; - g_mock_mcp_can_read_msg_buf_id = OSCC_THROTTLE_COMMAND_CAN_ID; - oscc_throttle_command_s * throttle_command = - (oscc_throttle_command_s *) g_mock_mcp_can_read_msg_buf_buf; + oscc_throttle_enable_s * throttle_enable = + (oscc_throttle_enable_s *) g_mock_mcp_can_read_msg_buf_buf; - throttle_command->magic[0] = OSCC_MAGIC_BYTE_0; - throttle_command->magic[1] = OSCC_MAGIC_BYTE_1; - throttle_command->enable = 1; + throttle_enable->magic[0] = OSCC_MAGIC_BYTE_0; + throttle_enable->magic[1] = OSCC_MAGIC_BYTE_1; check_for_incoming_message(); } @@ -16,15 +15,14 @@ WHEN("^an enable throttle command is received$") WHEN("^a disable throttle command is received$") { + g_mock_mcp_can_read_msg_buf_id = OSCC_THROTTLE_DISABLE_CAN_ID; g_mock_mcp_can_check_receive_return = CAN_MSGAVAIL; - g_mock_mcp_can_read_msg_buf_id = OSCC_THROTTLE_COMMAND_CAN_ID; - oscc_throttle_command_s * throttle_command = - (oscc_throttle_command_s *) g_mock_mcp_can_read_msg_buf_buf; + oscc_throttle_disable_s * throttle_disable = + (oscc_throttle_disable_s *) g_mock_mcp_can_read_msg_buf_buf; - throttle_command->magic[0] = OSCC_MAGIC_BYTE_0; - throttle_command->magic[1] = OSCC_MAGIC_BYTE_1; - throttle_command->enable = 0; + throttle_disable->magic[0] = OSCC_MAGIC_BYTE_0; + throttle_disable->magic[1] = OSCC_MAGIC_BYTE_1; check_for_incoming_message(); } @@ -58,7 +56,6 @@ WHEN("^a command is received with spoof values (.*) and (.*)$") throttle_command->magic[0] = OSCC_MAGIC_BYTE_0; throttle_command->magic[1] = OSCC_MAGIC_BYTE_1; - throttle_command->enable = 1; throttle_command->spoof_value_high = high; throttle_command->spoof_value_low = low; diff --git a/firmware/throttle/tests/features/step_definitions/test.cpp.orig b/firmware/throttle/tests/features/step_definitions/test.cpp.orig deleted file mode 100644 index ac0a65e2..00000000 --- a/firmware/throttle/tests/features/step_definitions/test.cpp.orig +++ /dev/null @@ -1,10 +0,0 @@ -// include source files to prevent step files from conflicting with each other -#include "common.cpp" -<<<<<<< HEAD -#include "checking_faults.cpp" -======= -#include "checking_actuator_functionality.cpp" -#include "checking_sensor_validity.cpp" ->>>>>>> 7573ad032a09a9325d6dc7400c19e9532fea7547 -#include "receiving_commands.cpp" -#include "sending_reports.cpp" diff --git a/firmware/throttle/tests/property/build.rs b/firmware/throttle/tests/property/build.rs index a7984ce7..53da6d28 100644 --- a/firmware/throttle/tests/property/build.rs +++ b/firmware/throttle/tests/property/build.rs @@ -23,6 +23,7 @@ fn main() { .file("../../src/communications.cpp") .file("../../src/throttle_control.cpp") .file("../../src/globals.cpp") + .cpp(true) .compile("libthrottle_test.a"); let out_dir = env::var("OUT_DIR").unwrap(); @@ -42,6 +43,8 @@ fn main() { .whitelisted_function("check_for_operator_override") .whitelisted_var("OSCC_MAGIC_BYTE_0") .whitelisted_var("OSCC_MAGIC_BYTE_1") + .whitelisted_var("OSCC_THROTTLE_ENABLE_CAN_ID") + .whitelisted_var("OSCC_THROTTLE_DISABLE_CAN_ID") .whitelisted_var("OSCC_THROTTLE_REPORT_CAN_ID") .whitelisted_var("OSCC_THROTTLE_REPORT_CAN_DLC") .whitelisted_var("OSCC_THROTTLE_COMMAND_CAN_ID") @@ -55,6 +58,8 @@ fn main() { .whitelisted_var("THROTTLE_SPOOF_LOW_SIGNAL_RANGE_MAX") .whitelisted_var("THROTTLE_SPOOF_HIGH_SIGNAL_RANGE_MIN") .whitelisted_var("THROTTLE_SPOOF_HIGH_SIGNAL_RANGE_MAX") + .whitelisted_type("oscc_throttle_enable_s") + .whitelisted_type("oscc_throttle_disable_s") .whitelisted_type("oscc_throttle_report_s") .whitelisted_type("oscc_throttle_command_s") .whitelisted_type("can_frame_s") diff --git a/firmware/throttle/tests/property/src/tests.rs b/firmware/throttle/tests/property/src/tests.rs index c60ae7d0..35e5366f 100644 --- a/firmware/throttle/tests/property/src/tests.rs +++ b/firmware/throttle/tests/property/src/tests.rs @@ -13,30 +13,37 @@ use quickcheck::{QuickCheck, TestResult, Arbitrary, StdGen, Gen}; use rand::Rng; extern "C" { - #[link_name = "g_mock_mcp_can_check_receive_return"] pub static mut g_mock_mcp_can_check_receive_return: u8; - #[link_name = "g_mock_mcp_can_read_msg_buf_id"] pub static mut g_mock_mcp_can_read_msg_buf_id: u32; - #[link_name = "g_mock_mcp_can_read_msg_buf_buf"] pub static mut g_mock_mcp_can_read_msg_buf_buf: [u8; 8usize]; - #[link_name = "g_mock_mcp_can_send_msg_buf_id"] pub static mut g_mock_mcp_can_send_msg_buf_id: u32; - #[link_name = "g_mock_mcp_can_send_msg_buf_ext"] pub static mut g_mock_mcp_can_send_msg_buf_ext: u8; - #[link_name = "g_mock_mcp_can_send_msg_buf_len"] pub static mut g_mock_mcp_can_send_msg_buf_len: u8; - #[link_name = "g_mock_mcp_can_send_msg_buf_buf"] pub static mut g_mock_mcp_can_send_msg_buf_buf: *mut u8; - #[link_name = "g_mock_arduino_analog_read_return"] - pub static mut g_mock_arduino_analog_read_return: isize; - #[link_name = "g_mock_dac_output_a"] + pub static mut g_mock_arduino_analog_read_return: [isize; 8usize]; pub static mut g_mock_dac_output_a: u16; - #[link_name = "g_mock_dac_output_b"] pub static mut g_mock_dac_output_b: u16; - #[link_name = "g_throttle_control_state"] pub static mut g_throttle_control_state: throttle_control_state_s; } +impl Arbitrary for oscc_throttle_enable_s { + fn arbitrary(g: &mut G) -> oscc_throttle_enable_s { + oscc_throttle_enable_s { + magic: [OSCC_MAGIC_BYTE_0 as u8, OSCC_MAGIC_BYTE_1 as u8], + reserved: [u8::arbitrary(g); 6], + } + } +} + +impl Arbitrary for oscc_throttle_disable_s { + fn arbitrary(g: &mut G) -> oscc_throttle_disable_s { + oscc_throttle_disable_s { + magic: [OSCC_MAGIC_BYTE_0 as u8, OSCC_MAGIC_BYTE_1 as u8], + reserved: [u8::arbitrary(g); 6], + } + } +} + impl Arbitrary for oscc_throttle_report_s { fn arbitrary(g: &mut G) -> oscc_throttle_report_s { oscc_throttle_report_s { @@ -44,7 +51,7 @@ impl Arbitrary for oscc_throttle_report_s { enabled: u8::arbitrary(g), operator_override: u8::arbitrary(g), dtcs: u8::arbitrary(g), - reserved: [u8::arbitrary(g); 3] + reserved: [u8::arbitrary(g); 3], } } } @@ -55,20 +62,18 @@ impl Arbitrary for oscc_throttle_command_s { magic: [OSCC_MAGIC_BYTE_0 as u8, OSCC_MAGIC_BYTE_1 as u8], spoof_value_low: u16::arbitrary(g), spoof_value_high: u16::arbitrary(g), - enable: u8::arbitrary(g), - reserved: u8::arbitrary(g) + reserved: [u8::arbitrary(g); 2], } } } - impl Arbitrary for can_frame_s { fn arbitrary(g: &mut G) -> can_frame_s { can_frame_s { id: u32::arbitrary(g), dlc: u8::arbitrary(g), timestamp: u32::arbitrary(g), - data: [u8::arbitrary(g); 8] + data: [u8::arbitrary(g); 8], } } } @@ -77,10 +82,12 @@ impl Arbitrary for can_frame_s { /// that are not throttle or fault commands /// this means that none of the throttle control state would /// change, nor would it output any values onto the DAC. -fn prop_only_process_valid_messages(rx_can_msg: can_frame_s, enabled: bool, operator_override: bool, dtcs: u8) -> TestResult { - if rx_can_msg.id == OSCC_THROTTLE_COMMAND_CAN_ID || - rx_can_msg.id == OSCC_FAULT_REPORT_CAN_ID - { +fn prop_only_process_valid_messages(rx_can_msg: can_frame_s, + enabled: bool, + operator_override: bool, + dtcs: u8) + -> TestResult { + if rx_can_msg.id == OSCC_THROTTLE_COMMAND_CAN_ID || rx_can_msg.id == OSCC_FAULT_REPORT_CAN_ID { return TestResult::discard(); } unsafe { @@ -96,8 +103,7 @@ fn prop_only_process_valid_messages(rx_can_msg: can_frame_s, enabled: bool, oper check_for_incoming_message(); - TestResult::from_bool(g_throttle_control_state.enabled == - enabled && + TestResult::from_bool(g_throttle_control_state.enabled == enabled && g_throttle_control_state.operator_override == operator_override && g_throttle_control_state.dtcs == dtcs && g_mock_dac_output_a == dac_a && @@ -110,21 +116,20 @@ fn check_message_type_validity() { QuickCheck::new() .tests(1000) .gen(StdGen::new(rand::thread_rng(), u32::max_value() as usize)) - .quickcheck(prop_only_process_valid_messages as fn(can_frame_s, bool, bool, u8) -> TestResult) + .quickcheck(prop_only_process_valid_messages as + fn(can_frame_s, bool, bool, u8) -> TestResult) } /// the throttle firmware should set the control state as enabled -/// upon reciept of a valid command throttle message telling it to enable -fn prop_process_enable_command(mut throttle_command_msg: oscc_throttle_command_s) -> TestResult { +/// upon reciept of a valid enable throttle message telling it to enable +fn prop_process_enable_command(throttle_enable_msg: oscc_throttle_enable_s) -> TestResult { unsafe { - throttle_command_msg.enable = 1u8; - g_throttle_control_state.enabled = false; g_throttle_control_state.operator_override = false; - g_mock_mcp_can_read_msg_buf_id = OSCC_THROTTLE_COMMAND_CAN_ID; + g_mock_mcp_can_read_msg_buf_id = OSCC_THROTTLE_ENABLE_CAN_ID; g_mock_mcp_can_check_receive_return = CAN_MSGAVAIL as u8; - g_mock_mcp_can_read_msg_buf_buf = std::mem::transmute(throttle_command_msg); + g_mock_mcp_can_read_msg_buf_buf = std::mem::transmute(throttle_enable_msg); check_for_incoming_message(); @@ -136,18 +141,19 @@ fn prop_process_enable_command(mut throttle_command_msg: oscc_throttle_command_s fn check_process_enable_command() { QuickCheck::new() .tests(1000) - .quickcheck(prop_process_enable_command as fn(oscc_throttle_command_s) -> TestResult) + .quickcheck(prop_process_enable_command as fn(oscc_throttle_enable_s) -> TestResult) } /// the throttle firmware should set the control state as disabled -/// upon reciept of a valid command throttle message telling it to disable -fn prop_process_disable_command(mut throttle_command_msg: oscc_throttle_command_s) -> TestResult { +/// upon reciept of a valid disable throttle message telling it to disable +fn prop_process_disable_command(throttle_disable_msg: oscc_throttle_disable_s) -> TestResult { unsafe { - throttle_command_msg.enable = 0u8; + g_throttle_control_state.enabled = true; + g_throttle_control_state.operator_override = false; - g_mock_mcp_can_read_msg_buf_id = OSCC_THROTTLE_COMMAND_CAN_ID; - g_mock_mcp_can_read_msg_buf_buf = std::mem::transmute(throttle_command_msg); + g_mock_mcp_can_read_msg_buf_id = OSCC_THROTTLE_DISABLE_CAN_ID; g_mock_mcp_can_check_receive_return = CAN_MSGAVAIL as u8; + g_mock_mcp_can_read_msg_buf_buf = std::mem::transmute(throttle_disable_msg); check_for_incoming_message(); @@ -159,15 +165,18 @@ fn prop_process_disable_command(mut throttle_command_msg: oscc_throttle_command_ fn check_process_disable_command() { QuickCheck::new() .tests(1000) - .quickcheck(prop_process_disable_command as fn(oscc_throttle_command_s) -> TestResult) + .quickcheck(prop_process_disable_command as fn(oscc_throttle_disable_s) -> TestResult) } /// the throttle firmware should send requested spoof values /// upon recieving a throttle command message fn prop_output_accurate_spoofs(mut throttle_command_msg: oscc_throttle_command_s) -> TestResult { - throttle_command_msg.enable = 1u8; - throttle_command_msg.spoof_value_low = rand::thread_rng().gen_range(THROTTLE_SPOOF_LOW_SIGNAL_RANGE_MIN as u16, THROTTLE_SPOOF_LOW_SIGNAL_RANGE_MAX as u16); - throttle_command_msg.spoof_value_high = rand::thread_rng().gen_range(THROTTLE_SPOOF_HIGH_SIGNAL_RANGE_MIN as u16, THROTTLE_SPOOF_HIGH_SIGNAL_RANGE_MAX as u16); + throttle_command_msg.spoof_value_low = + rand::thread_rng().gen_range(THROTTLE_SPOOF_LOW_SIGNAL_RANGE_MIN as u16, + THROTTLE_SPOOF_LOW_SIGNAL_RANGE_MAX as u16); + throttle_command_msg.spoof_value_high = + rand::thread_rng().gen_range(THROTTLE_SPOOF_HIGH_SIGNAL_RANGE_MIN as u16, + THROTTLE_SPOOF_HIGH_SIGNAL_RANGE_MAX as u16); unsafe { g_throttle_control_state.enabled = true; @@ -177,9 +186,8 @@ fn prop_output_accurate_spoofs(mut throttle_command_msg: oscc_throttle_command_s check_for_incoming_message(); - TestResult::from_bool(g_mock_dac_output_b == throttle_command_msg.spoof_value_low && - g_mock_dac_output_a == - throttle_command_msg.spoof_value_high ) + TestResult::from_bool(g_mock_dac_output_b == throttle_command_msg.spoof_value_low && + g_mock_dac_output_a == throttle_command_msg.spoof_value_high) } } @@ -193,18 +201,12 @@ fn check_output_accurate_spoofs() { /// the throttle firmware should constrain requested spoof values /// upon recieving a throttle command message -fn prop_output_constrained_spoofs(mut throttle_command_msg: oscc_throttle_command_s) -> TestResult { - throttle_command_msg.enable = 1u8; +fn prop_output_constrained_spoofs(throttle_command_msg: oscc_throttle_command_s) -> TestResult { unsafe { - if (throttle_command_msg.spoof_value_low >= - THROTTLE_SPOOF_HIGH_SIGNAL_RANGE_MIN as u16 && - throttle_command_msg.spoof_value_low <= - THROTTLE_SPOOF_HIGH_SIGNAL_RANGE_MAX as u16) || - (throttle_command_msg.spoof_value_high >= - THROTTLE_SPOOF_HIGH_SIGNAL_RANGE_MIN as u16 && - throttle_command_msg.spoof_value_high <= - THROTTLE_SPOOF_HIGH_SIGNAL_RANGE_MAX as u16) - { + if (throttle_command_msg.spoof_value_low >= THROTTLE_SPOOF_LOW_SIGNAL_RANGE_MIN as u16 && + throttle_command_msg.spoof_value_low <= THROTTLE_SPOOF_LOW_SIGNAL_RANGE_MAX as u16) || + (throttle_command_msg.spoof_value_high >= THROTTLE_SPOOF_HIGH_SIGNAL_RANGE_MIN as u16 && + throttle_command_msg.spoof_value_high <= THROTTLE_SPOOF_HIGH_SIGNAL_RANGE_MAX as u16) { return TestResult::discard(); } @@ -216,11 +218,10 @@ fn prop_output_constrained_spoofs(mut throttle_command_msg: oscc_throttle_comman check_for_incoming_message(); - TestResult::from_bool( - g_mock_dac_output_a >= THROTTLE_SPOOF_HIGH_SIGNAL_RANGE_MIN as u16 && - g_mock_dac_output_a <= THROTTLE_SPOOF_HIGH_SIGNAL_RANGE_MAX as u16 && - g_mock_dac_output_b >= THROTTLE_SPOOF_HIGH_SIGNAL_RANGE_MIN as u16 && - g_mock_dac_output_b <= THROTTLE_SPOOF_HIGH_SIGNAL_RANGE_MAX as u16) + TestResult::from_bool(g_mock_dac_output_a >= THROTTLE_SPOOF_HIGH_SIGNAL_RANGE_MIN as u16 && + g_mock_dac_output_a <= THROTTLE_SPOOF_HIGH_SIGNAL_RANGE_MAX as u16 && + g_mock_dac_output_b >= THROTTLE_SPOOF_LOW_SIGNAL_RANGE_MIN as u16 && + g_mock_dac_output_b <= THROTTLE_SPOOF_LOW_SIGNAL_RANGE_MAX as u16) } } @@ -233,10 +234,7 @@ fn check_output_constrained_spoofs() { } /// the throttle firmware should create only valid CAN frames -fn prop_send_valid_can_fields(enabled: bool, - operator_override: bool, - dtcs: u8) - -> TestResult { +fn prop_send_valid_can_fields(enabled: bool, operator_override: bool, dtcs: u8) -> TestResult { unsafe { g_throttle_control_state.operator_override = operator_override; g_throttle_control_state.enabled = enabled; @@ -246,8 +244,9 @@ fn prop_send_valid_can_fields(enabled: bool, let throttle_report_msg = g_mock_mcp_can_send_msg_buf_buf as *mut oscc_throttle_report_s; - TestResult::from_bool((*throttle_report_msg).enabled == enabled as u8 &&(*throttle_report_msg).operator_override == operator_override as u8 && - (*throttle_report_msg).dtcs == dtcs) + TestResult::from_bool((*throttle_report_msg).enabled == enabled as u8 && + (*throttle_report_msg).operator_override == operator_override as u8 && + (*throttle_report_msg).dtcs == dtcs) } } @@ -265,13 +264,15 @@ fn prop_check_operator_override(analog_read_spoof: u16) -> TestResult { unsafe { g_throttle_control_state.enabled = true; g_throttle_control_state.operator_override = false; - g_mock_arduino_analog_read_return = analog_read_spoof as isize; + g_mock_arduino_analog_read_return[0] = analog_read_spoof as isize; + g_mock_arduino_analog_read_return[1] = analog_read_spoof as isize; check_for_operator_override(); if analog_read_spoof >= (ACCELERATOR_OVERRIDE_THRESHOLD as u16) { - TestResult::from_bool(g_throttle_control_state.operator_override == true && g_throttle_control_state.enabled == false && - g_mock_mcp_can_send_msg_buf_id == OSCC_FAULT_REPORT_CAN_ID) + TestResult::from_bool(g_throttle_control_state.operator_override == true && + g_throttle_control_state.enabled == false && + g_mock_mcp_can_send_msg_buf_id == OSCC_FAULT_REPORT_CAN_ID) } else { TestResult::from_bool(g_throttle_control_state.operator_override == false) } @@ -282,7 +283,6 @@ fn prop_check_operator_override(analog_read_spoof: u16) -> TestResult { fn check_operator_override() { QuickCheck::new() .tests(1000) - .gen(StdGen::new(rand::thread_rng(), u16::max_value() as usize)) .quickcheck(prop_check_operator_override as fn(u16) -> TestResult) } diff --git a/hardware/boards/actuator_control_board/actuator_control_board_1.0.0.brd b/hardware/boards/actuator_control/actuator_control_1.2.0.brd similarity index 84% rename from hardware/boards/actuator_control_board/actuator_control_board_1.0.0.brd rename to hardware/boards/actuator_control/actuator_control_1.2.0.brd index dd59ca69..a92b1f0d 100644 --- a/hardware/boards/actuator_control_board/actuator_control_board_1.0.0.brd +++ b/hardware/boards/actuator_control/actuator_control_1.2.0.brd @@ -1,6 +1,6 @@ - + @@ -20,12 +20,12 @@ - - - - - - + + + + + + @@ -160,21 +160,19 @@ -GND -+12V -BM2 -GND +GND ++12V NO NO COM COM NC NC -14 -9 -10 -11 -13 +PFL +PACC +PMC1 +PMC2 +PFR @@ -217,11 +215,10 @@ -B2 -B1 +S P VCM -GND +E CAN H L @@ -242,10 +239,10 @@ S4 + - -S5 +S5 + - -S6 +S6 + - S7 @@ -259,6 +256,15 @@ +SLAFR +SLRFR +PCK1 +PCK2 +MTT +Pump +GND +GND ++12V @@ -576,9643 +582,8 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + @@ -14208,6 +4579,10341 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + @@ -14903,6 +15609,9 @@ + + + @@ -14994,14 +15703,14 @@ - - + + - - + + - - + + @@ -15019,143 +15728,143 @@ - + + - + - - + - + + - - + - + + - + - - + - + + - + - - + - + + - + - - + - + + - + - + - - + - + + - + - - + - + - + - + + - - + - + + - + - - + - + + - @@ -15186,88 +15895,88 @@ - + - + + - + - - + - + - - - - + + + + + + - - + - + - - + - + - + - + + - - + - + + - - + + - + - - + - + @@ -15275,58 +15984,58 @@ + - + - + - - + - + - + - + + - - + - + + - - + + - + - - + - + @@ -15334,58 +16043,58 @@ + - + - + - - + - + - + - + + - - + - + + - - + + - + - - + - + @@ -15393,126 +16102,126 @@ + - + - + - - + - + - + - + + - - + - + + - + - + - - + - + + - + - - + - + - + - + + - - + - + + - - + - + + - - + - + + - - + + - + - - + - + @@ -15524,53 +16233,53 @@ + - + - - + - + - + - + + - - + - + + - - + + - + - - + - + @@ -15578,58 +16287,58 @@ + - + - + - - + - + - + - + + - - + - + + - - + + - + - - + - + @@ -15637,58 +16346,58 @@ + - + - + - - + - + - + - + + - - + - + + - - + + - + - - + - + @@ -15696,107 +16405,107 @@ + - + - + - - + - + - + - + + - - + - + + - - + - + + - - + - + + - - + - + + - - + - + + - + - + - - + - + + - + - - + - + @@ -15814,24 +16523,24 @@ + - + - - + - + - + - + + - @@ -15839,1237 +16548,1309 @@ - + - + + - - - + + - + - + + - + - - - - - - - + - + + - - + - + + - - + - + + - - + - + + - - + - + + - - + - + + - - + - + + - - + - + + - - + - + + - - + - + + - + - + - - + - + + - + - - + - + + - - + - + + - + - + - - + - + - + - + + - - + - + + - - + - + + - - + - + + - - + - + + - - + - + + - - + - + + - + - + - - + - + + - + - - + - + + - - + - + + - + - + - - + - + - + - + + - - + - + + - - + - + + - - + - + + - - + - + + - - + - + + - - + - + + - + - + - - + - + + - + - - + - + + - - + - + + - + - + - - + - + - + - + + - - + - + + - - + - + + - - + - + + - - + - + + - - + - + + - - + - + + - + - + - - + - + + - + - - + - + + - - + - + + - + - + - - + - + - + - + + - - + - + + - - + - + + - - + - + + - - + - + + - - + - + + - - + - + + - + - + - - + - + + - + - - + - + + - - + - + + - + - + - - + - + - + - + + - - + - + + - - + - + + - - + - + + - - + - + + - - + - + + - - + - + + - + - + - - + - + + - + - - + - + + - - + - + + - + - + - - + - + - + - + + - - + - + + - - + - + + - - + - + + - - + - + + - - + - + + - - + - + + - + - + - - + - + + - + - - + - + + - - + - + + - + - + - - + - + - + - + + - - + - + + - - + - + + - - + - + + - - + - + + - - + - + + - - + - + + - + - + - - + - + + - + - - + - + + - - + - + + - + - + - - + - + - + - + + - - - + + - - + + - + - + + - - + - + + - + - + - - + - + + - + - - + - + + - + - - + - + + - + - - + - + - + - + + - - + - + + - - + - + + - - + - + + - - + - + + - - + - + + - - + - + + - - + - + + - - + - + + - - + - + + - - - - + + + - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + @@ -17080,8 +17861,9 @@ - - + + + @@ -17132,9 +17914,11 @@ - - + + + + @@ -17143,39 +17927,33 @@ - - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + - - - - - - - + + + + + + + + @@ -17450,14 +18228,17 @@ - - + + + - - + + + + @@ -17493,18 +18274,18 @@ - - - + + + - - - - + + + + @@ -17627,9 +18408,6 @@ - - - @@ -17658,6 +18436,12 @@ + + + + + + @@ -17666,11 +18450,13 @@ - - + + + + @@ -17695,9 +18481,6 @@ - - - @@ -17791,9 +18574,6 @@ - - - @@ -18377,9 +19157,7 @@ - - - + @@ -18388,9 +19166,7 @@ - - - + @@ -18405,36 +19181,32 @@ - - + + + - - + + + - - + + + - - + + + - - - - - - - - - + @@ -18445,17 +19217,6 @@ - - - - - - - - - - - @@ -18486,30 +19247,6 @@ - - - - - - - - - - - - - - - - - - - - - - - - @@ -18537,16 +19274,44 @@ - - - - - - - - - - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + @@ -18558,11 +19323,11 @@ - - - - - + + + + + @@ -18655,6 +19420,18 @@ + + + + + + + + + + + + @@ -19014,9 +19791,6 @@ - - - @@ -19027,6 +19801,11 @@ + + + + + @@ -19462,8 +20241,10 @@ - - + + + + @@ -19613,43 +20394,51 @@ - + + + - - + + + + - + + + + - - + + + - - + + + + + + - - - - - - - + + + @@ -19657,19 +20446,31 @@ + + + + + + + + - - - - - - - + + + + + + + + + + + @@ -19718,9 +20519,9 @@ - - - + + + @@ -19730,9 +20531,9 @@ - - - + + + @@ -19989,14 +20790,13 @@ - - - - + + + @@ -20101,7 +20901,7 @@ - + @@ -20110,17 +20910,16 @@ - - - - + + + - + @@ -20430,7 +21229,7 @@ - + @@ -20509,100 +21308,188 @@ - - - + + + + + + + + + + + + + + + + + + + + + + - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/hardware/boards/actuator_control/actuator_control_1.2.0.pdf b/hardware/boards/actuator_control/actuator_control_1.2.0.pdf new file mode 100644 index 00000000..122b8af4 Binary files /dev/null and b/hardware/boards/actuator_control/actuator_control_1.2.0.pdf differ diff --git a/hardware/boards/actuator_control_board/actuator_control_board_1.0.0.sch b/hardware/boards/actuator_control/actuator_control_1.2.0.sch similarity index 98% rename from hardware/boards/actuator_control_board/actuator_control_board_1.0.0.sch rename to hardware/boards/actuator_control/actuator_control_1.2.0.sch index fa4745b0..583aca73 100644 --- a/hardware/boards/actuator_control_board/actuator_control_board_1.0.0.sch +++ b/hardware/boards/actuator_control/actuator_control_1.2.0.sch @@ -1,6 +1,6 @@ - + @@ -8727,7 +8727,6 @@ Source: 008-0260-0_E.pdf - @@ -8816,11 +8815,6 @@ Source: 008-0260-0_E.pdf - - - - - @@ -9009,13 +9003,33 @@ Source: 008-0260-0_E.pdf - + + + + + + + + + + + + + + + + + + + + + @@ -9109,6 +9123,9 @@ Source: 008-0260-0_E.pdf + + + @@ -9202,6 +9219,11 @@ Source: 008-0260-0_E.pdf + + + + + @@ -9492,32 +9514,6 @@ Source: 008-0260-0_E.pdf - - - - - - - - - - - - - - - - - - - - - - - - - @@ -9559,6 +9555,36 @@ Source: 008-0260-0_E.pdf + + + + + + + + + + + + + + + + + + + + + + + + + + @@ -9632,6 +9658,17 @@ Source: 008-0260-0_E.pdf + + + + + + + + + + @@ -9706,11 +9743,6 @@ Source: 008-0260-0_E.pdf - - - - - @@ -9813,13 +9845,6 @@ Source: 008-0260-0_E.pdf - - - - - - - @@ -10107,33 +10132,7 @@ Source: 008-0260-0_E.pdf - - - - - - - - - - - - - - - - - - - - - - - - - - + @@ -10176,6 +10175,31 @@ Source: 008-0260-0_E.pdf + + + + + + + + + + + + + + + + + + + + + @@ -11553,29 +11577,8 @@ Source: 008-0260-0_E.pdf - - - - - - - - - - - - - - - - - - - - - @@ -11696,23 +11699,12 @@ Source: 008-0260-0_E.pdf - - - - - - - - - - - - - - - - - - - - - - - - @@ -12149,43 +12128,8 @@ Source: 008-0260-0_E.pdf - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + - + - + + +Actuator Test + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/hardware/boards/actuator_control_board/actuator_control_board_sch_1.0.0.pdf b/hardware/boards/actuator_control_board/actuator_control_board_sch_1.0.0.pdf deleted file mode 100644 index 7920cead..00000000 Binary files a/hardware/boards/actuator_control_board/actuator_control_board_sch_1.0.0.pdf and /dev/null differ diff --git a/hardware/boards/sensor_interface/sensor_interface_1.1.0.brd b/hardware/boards/sensor_interface/sensor_interface_1.1.0.brd new file mode 100644 index 00000000..d76a162e --- /dev/null +++ b/hardware/boards/sensor_interface/sensor_interface_1.1.0.brd @@ -0,0 +1,15796 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +CANH +CANL + + + + + + + + + + + + + + + + + + + ++12V +GND +PWR +CAN-TX +CAN-RX +INT + + + + + + + + + + + + + + +SIG +IN +A +SIG +IN +B +SIG +OUTB + +GND +GND +GND +GND +A + + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + + + + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + +Plastic- encapsulated transistors + + +<b>CRYSTAL</b> + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + +>name + + + + + + + + + + + + + + + + + + + + + + + + + +>NAME + + + + + + + + + +>NAME + + + + + + + + + + + + + + + +>NAME + + + + + + + + +>NAME + + + + + + + + +>NAME + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +>NAME + + + + + + +<b>Description:</b> Standard 0402 Package for Resistors<br/> + + + + + + +>NAME + + +<b>Description:</b> Standard 0805 Package for Capacitors<br/> + + + + + + +>NAME + + +<b>Description:</b> Standard 0402 Package for Capacitors<br/> + + + + + + +>NAME + + + + + + + + +>NAME + + + + + + + + +<b>Description:</b> Footprint for Single LEDs in 0603<br/> + + + + + + + + + + + + +>NAME + + + + + + + + + +<b>Jumpers</b><p> +<author>Created by librarian@cadsoft.de</author> + + +<b>JUMPER</b> + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + + +Generated from <b>polysync_steering_throttle.sch</b><p> +by exp-lbrs.ulp + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +8 +9 +10 +11 +12 +13 +GND +AREF +SDA +SCL +JP1 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +0 +1 +2 +3 +4 +5 +6 +7 +JP2 + + + + + + + + + + + + + + + + + + + + + + + + + + + + +JP3 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +1 +0 +2 +4 +5 +ANALOG +3 +JP4 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +RST +3V3 +5V +GND +Vin +IOREF +NC +JP5 + + + + + + + + + + + + + + +<b>MacroFab, INC. EAGLE Design Rules</b> +<p>This DRC check is for 2-Layer Standard Capability boards to be manufactured through the MacroFab, INC. service. + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +Since Version 6.2.2 text objects can contain more than one line, +which will not be processed correctly with this version. + + + diff --git a/hardware/boards/sensor_interface/sensor_interface_1.1.0.pdf b/hardware/boards/sensor_interface/sensor_interface_1.1.0.pdf new file mode 100644 index 00000000..6a55743f Binary files /dev/null and b/hardware/boards/sensor_interface/sensor_interface_1.1.0.pdf differ diff --git a/hardware/boards/sensor_interface_board/sensor_interface_board_1.0.0.sch b/hardware/boards/sensor_interface/sensor_interface_1.1.0.sch similarity index 97% rename from hardware/boards/sensor_interface_board/sensor_interface_board_1.0.0.sch rename to hardware/boards/sensor_interface/sensor_interface_1.1.0.sch index 98094850..148a11a9 100644 --- a/hardware/boards/sensor_interface_board/sensor_interface_board_1.0.0.sch +++ b/hardware/boards/sensor_interface/sensor_interface_1.1.0.sch @@ -1,6 +1,6 @@ - + @@ -1782,6 +1782,25 @@ Source: 008-0260-0_E.pdf >NAME + + + + + + + + + + + + + + + + +>NAME +>VALUE + @@ -5869,6 +5888,22 @@ Source: 008-0260-0_E.pdf + + + + + + + + + + + + + +>NAME +>VALUE + @@ -5990,6 +6025,28 @@ Source: 008-0260-0_E.pdf + + + + + + + + + + + + + + + + + + + + + + @@ -7431,14 +7488,14 @@ by exp-lbrs.ulp - + - + - + - + @@ -7447,13 +7504,13 @@ by exp-lbrs.ulp - + - - + + @@ -7471,6 +7528,18 @@ by exp-lbrs.ulp + + + + + + + + + + + + @@ -7487,10 +7556,10 @@ by exp-lbrs.ulp - - - - + + + + @@ -7522,19 +7591,19 @@ by exp-lbrs.ulp - - - - - - - - - - - - - + + + + + + + + + + + + + @@ -7544,8 +7613,8 @@ by exp-lbrs.ulp - - + + @@ -7554,18 +7623,18 @@ by exp-lbrs.ulp - - - - - - - - - - - - + + + + + + + + + + + + @@ -7575,6 +7644,21 @@ by exp-lbrs.ulp + + + + + + + + + + + + + + + @@ -7597,7 +7681,7 @@ by exp-lbrs.ulp - + @@ -7654,38 +7738,38 @@ by exp-lbrs.ulp - - + + - - + + - - - + + + - - + + - - - + + + - + - + @@ -7700,22 +7784,22 @@ by exp-lbrs.ulp - + - + - + - + @@ -7737,6 +7821,31 @@ by exp-lbrs.ulp + + + + + + + + + + + + + + + + + + + + + + + + + @@ -7745,11 +7854,11 @@ by exp-lbrs.ulp - - @@ -7790,11 +7899,11 @@ by exp-lbrs.ulp - - - - - @@ -7806,11 +7915,11 @@ by exp-lbrs.ulp - - - - - @@ -7822,11 +7931,11 @@ by exp-lbrs.ulp - - - - - @@ -7900,8 +8009,8 @@ by exp-lbrs.ulp - - @@ -7931,11 +8040,11 @@ by exp-lbrs.ulp - - - - - @@ -7982,14 +8091,14 @@ by exp-lbrs.ulp - - + + - - + + @@ -8087,15 +8196,15 @@ by exp-lbrs.ulp - - - + + + - - + + - - + + @@ -8181,6 +8290,16 @@ by exp-lbrs.ulp + + + + + + + + + + @@ -8203,8 +8322,12 @@ by exp-lbrs.ulp - - @@ -8221,9 +8344,9 @@ by exp-lbrs.ulp - - - @@ -8240,9 +8363,9 @@ by exp-lbrs.ulp - - - @@ -8254,8 +8377,12 @@ by exp-lbrs.ulp - - @@ -8266,15 +8393,14 @@ by exp-lbrs.ulp @@ -8285,15 +8411,14 @@ by exp-lbrs.ulp @@ -8349,7 +8474,7 @@ by exp-lbrs.ulp - + @@ -8383,11 +8508,11 @@ by exp-lbrs.ulp - - - + + + - + @@ -8441,6 +8566,34 @@ by exp-lbrs.ulp + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/hardware/boards/sensor_interface_board/sensor_interface.brd b/hardware/boards/sensor_interface_board/sensor_interface.brd deleted file mode 100644 index cd83b6e1..00000000 --- a/hardware/boards/sensor_interface_board/sensor_interface.brd +++ /dev/null @@ -1,7663 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -CANH -CANL - - - - - - - - - - - - - - - - - - - - -+12V -GND -PWR -CAN-TX -CAN-RX -INT - - - - - - - - - - - - - - -SIG -IN -A -SIG -IN -B -SIG -OUTB - -GND -GND -GND -GND -A - - - - - - - - - - - - - - - - - - - - ->NAME ->VALUE - - - - - - - - - - - - - - - - - - - - - - - - - - - - ->NAME ->VALUE - - - - -Plastic- encapsulated transistors - - -<b>CRYSTAL</b> - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - ->NAME ->VALUE - - - - - ->name - - - - - - - - - - - - - - - - - - - - - - - - - ->NAME - - - - - - - - - ->NAME - - - - - - - - - - - - - - - ->NAME - - - - - - - - ->NAME - - - - - - - - ->NAME - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - ->NAME - - - - - - -<b>Description:</b> Standard 0402 Package for Resistors<br/> - - - - - - ->NAME - - -<b>Description:</b> Standard 0805 Package for Capacitors<br/> - - - - - - ->NAME - - -<b>Description:</b> Standard 0402 Package for Capacitors<br/> - - - - - - ->NAME - - - - - - - - ->NAME - - - - - - - - -<b>Description:</b> Footprint for Single LEDs in 0603<br/> - - - - - - - - - - - - ->NAME - - - - - - - - - -<b>Jumpers</b><p> -<author>Created by librarian@cadsoft.de</author> - - -<b>JUMPER</b> - - - - - - - - - - - - - - - - ->NAME ->VALUE - - - - - - -Generated from <b>polysync_steering_throttle.sch</b><p> -by exp-lbrs.ulp - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -8 -9 -10 -11 -12 -13 -GND -AREF -SDA -SCL -JP1 - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -0 -1 -2 -3 -4 -5 -6 -7 -JP2 - - - - - - - - - - - - - - - - - - - - - - - - - - - - -JP3 - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -1 -0 -2 -4 -5 -ANALOG -3 -JP4 - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -RST -3V3 -5V -GND -Vin -IOREF -NC -JP5 - - - - - - - - - - - - - - -<b>MacroFab, INC. EAGLE Design Rules</b> -<p>This DRC check is for 2-Layer Standard Capability boards to be manufactured through the MacroFab, INC. service. - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -Since Version 6.2.2 text objects can contain more than one line, -which will not be processed correctly with this version. - - - diff --git a/hardware/boards/sensor_interface_board/sensor_interface_BOM.xlsx b/hardware/boards/sensor_interface_board/sensor_interface_BOM.xlsx deleted file mode 100644 index 3a032f6b..00000000 Binary files a/hardware/boards/sensor_interface_board/sensor_interface_BOM.xlsx and /dev/null differ diff --git a/hardware/boards/sensor_interface_board/sensor_interface_board_sch_1.0.0.pdf b/hardware/boards/sensor_interface_board/sensor_interface_board_sch_1.0.0.pdf deleted file mode 100644 index 546d7ea2..00000000 Binary files a/hardware/boards/sensor_interface_board/sensor_interface_board_sch_1.0.0.pdf and /dev/null differ diff --git a/hardware/boards/vehicle_control_module/vehicle_controL_module_0.1.0.brd b/hardware/boards/vehicle_control_module/vehicle_controL_module_0.1.0.brd new file mode 100644 index 00000000..922caaff --- /dev/null +++ b/hardware/boards/vehicle_control_module/vehicle_controL_module_0.1.0.brd @@ -0,0 +1,17009 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +CANH +CANL + + + + + + + + + + + + + + + ++12V +GND +PWR +CAN-TX +CAN-RX +INT + + + + + + + + + + + + + + +A +SIG +IN +B +GND +GND + +A +SIG +OUT +B +GND +GND +NO COM NC +NO COM +NC + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + + + + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + +Plastic- encapsulated transistors + + +<b>CRYSTAL</b> + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + +>name + + + + + + + + + + + + + + + + + + + + + + + + + +>NAME + + + + + + + + + +>NAME + + + + + + + + + + + + + + + +>NAME + + + + + + + + +>NAME + + + + + + + + +>NAME + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + + + + +>NAME + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +>NAME + + + + + + +<b>Description:</b> Standard 0402 Package for Resistors<br/> + + + + + + +>NAME + + +<b>Description:</b> Standard 0805 Package for Capacitors<br/> + + + + + + +>NAME + + +<b>Description:</b> Standard 0402 Package for Capacitors<br/> + + + + + + +>NAME + + + + + + + + +>NAME + + + + + + + + +<b>Description:</b> Footprint for Single LEDs in 0603<br/> + + + + + + + + + + + + +>NAME + + + + + + + + + +<b>Jumpers</b><p> +<author>Created by librarian@cadsoft.de</author> + + +<b>JUMPER</b> + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + + +Generated from <b>polysync_steering_throttle.sch</b><p> +by exp-lbrs.ulp + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +8 +9 +10 +11 +12 +13 +GND +AREF +SDA +SCL +JP1 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +0 +1 +2 +3 +4 +5 +6 +7 +JP2 + + + + + + + + + + + + + + + + + + + + + + + + + + + + +JP3 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +1 +0 +2 +4 +5 +ANALOG +3 +JP4 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +RST +3V3 +5V +GND +Vin +IOREF +NC +JP5 + + + + + + + + + + + + + + +<b>MacroFab, INC. EAGLE Design Rules</b> +<p>This DRC check is for 2-Layer Standard Capability boards to be manufactured through the MacroFab, INC. service. + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +Since Version 6.2.2 text objects can contain more than one line, +which will not be processed correctly with this version. + + + diff --git a/hardware/boards/vehicle_control_module/vehicle_control_module_0.1.0.pdf b/hardware/boards/vehicle_control_module/vehicle_control_module_0.1.0.pdf new file mode 100644 index 00000000..0630fca7 Binary files /dev/null and b/hardware/boards/vehicle_control_module/vehicle_control_module_0.1.0.pdf differ diff --git a/hardware/boards/vehicle_control_module/vehicle_control_module_0.1.0.sch b/hardware/boards/vehicle_control_module/vehicle_control_module_0.1.0.sch new file mode 100644 index 00000000..78475801 --- /dev/null +++ b/hardware/boards/vehicle_control_module/vehicle_control_module_0.1.0.sch @@ -0,0 +1,8800 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + + + + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + + + + +>name +>value + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + +High-Speed CAN Transceiver<p/> +http://ww1.microchip.com/downloads/en/devicedoc/21667f.pdf + + + + + + + + + + + + + + + + + + + + + + +Stand-Alone CAN Controller With SPI Interface + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +Plastic- encapsulated transistors + + +<b>CRYSTAL</b> + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + + + +<b>CRYSTAL</b> + + + + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + +<b>CRYSTAL</b> + + + + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + +<b>CRYSTAL</b> + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + +<b>CRYSTAL</b> + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + +<b>CRYSTAL</b> + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + + + + + + + +<b>CRYSTAL</b> + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + + + + + + + +<b>CRYSTAL</b> + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + +<b>CRYSTAL</b> + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + +<b>CRYSTAL</b> + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + +<b>CRYSTAL</b> + + + + + + + + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + +<b>CRYSTAL</b> + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + +<b>CRYSTAL</b> + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + + + + + +<b>CRYSTAL</b> + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + +<b>CRYSTAL</b> + + + + + + + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + +<b>CRYSTAL</b> + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + +<b>CRYSTAL</b> + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + +<b>CRYSTAL RESONATOR</b> + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + +<b>CRYSTAL</b> + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + +<b>CRYSTAL</b> + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + +<b>Model 406 6.0x3.5mm Low Cost Surface Mount Crystal</b><p> +Source: 008-0260-0_E.pdf + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + +3.2mm*5mm dimension <br> +8MHz available + + + + + + + + + + + + + + + + + + +>name +>value +>name + + + + + +3.6mm*6mm dimension <br> +12MHz available + + + + + + + + + + + + + + + + + + + + + + +>name +>value +>name + + + + + +4.5mm*8mm dimension <br> +12MHz available + + + + + + + + + + + + + + + + + + + + + + +>name +>value +>name + + + + + + + + + + + + +>VALUE +>NAME + + + + + + + + + + + + + + +>name +>value + + + + + + + + + +>name +>value + + + + + + + + + +>NAME +>VALUE + + + + +>name + + + + +>name + + + + + + + +>name +>value + + + + + + + + + + + + + + + + + + +>NAME +>VALUE +1 +2 + + + + +>name + + + + + + + +<b>CRYSTAL</b> + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +<b>Frames for Sheet and Layout</b> + + + + + + + + + + + + + + + + + + + + + + + + + + +Date: +>LAST_DATE_TIME +Sheet: +>SHEET +REV: +TITLE: +Document Number: +>DRAWING_NAME + + + + +<b>FRAME</b> A Size , 8 1/2 x 11 INCH, Landscape<p> + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +>NAME + + + + + + + + + +>NAME + + + + + + + + + + + + + + + +>NAME + + + + + + + + +>NAME + + + + + + + + +>NAME + + + + + + + + + + + + + + + + + + + + + + +>NAME + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + + + + +>NAME + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + + + + + +>NAME +>VALUE + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + ++ +- + + + + +>NAME +>VALUE + + + + + + + + +>NAME + + + + + + + + + + +>NAME + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + + + + + +>NAME + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +<b>Supply Symbols</b><p> + GND, VCC, 0V, +5V, -5V, etc.<p> + Please keep in mind, that these devices are necessary for the + automatic wiring of the supply signals.<p> + The pin name defined in the symbol is identical to the net which is to be wired automatically.<p> + In this library the device names are the same as the pin names of the symbols, therefore the correct signal names appear next to the supply symbols in the schematic.<p> + <author>Created by librarian@cadsoft.de</author> + + + + + +>VALUE + + + + + +>VALUE + + + + + + +>VALUE + + + + + +>VALUE + + + + + +<b>SUPPLY SYMBOL</b> + + + + + + + + + + + + +<b>SUPPLY SYMBOL</b> + + + + + + + + + + + + +<b>SUPPLY SYMBOL</b> + + + + + + + + + + + + +<b>SUPPLY SYMBOL</b> + + + + + + + + + + + + + + + + + + + + + + + + + + +>NAME + + + + + + + + + + + + + + + + + + + + + + + + + + + +>VALUE +>NAME + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +<b>Description:</b> Standard 0402 Package for Resistors<br/> + + + + + + +>NAME + + +<b>Description:</b> Standard 0603 Package for Resistors<br/> + + + + + + +>NAME + + +<b>Description:</b> Standard 0805 Package for Resistors<br/> + + + + + + +>NAME + + +<b>Description:</b> Standard 1206 Package for Resistors<br/> + + + + + + +>NAME + + +<b>Description:</b> Standard 1210 Package for Resistors<br/> + + + + + + +>NAME + + +<b>Description:</b> Standard 0402 Package for Capacitors<br/> + + + + + + +>NAME + + +<b>Description:</b> Standard 0603 Package for Capacitors<br/> + + + + + + +>NAME + + +<b>Description:</b> Standard 0805 Package for Capacitors<br/> + + + + + + +>NAME + + +<b>Description:</b> Standard 1206 Package for Capacitors<br/> + + + + + + +>NAME + + +<b>Description:</b> Standard 1210 Package for Capacitors<br/> + + + + + + +>NAME + + +<b>Description:</b> 4MM Round Package for Electrolytic Capacitors. Based on Panasonic Electrolytic Capacitors.<br> + + + + + + + + + + +>NAME + + + + +<b>Description:</b> 6.3MM Round Package for Electrolytic Capacitors. Based on Panasonic Electrolytic Capacitors.<br> + + + + + + + + + + + + +>NAME + + +<b>Description:</b> 8MM Round Package for Electrolytic Capacitors. Based on Panasonic Electrolytic Capacitors.<br> + + + + + + + + + + + + +>NAME + + +<b>Description:</b> 10MM Round Package for Electrolytic Capacitors. Based on Panasonic Electrolytic Capacitors. +<br/> + + +>NAME + + + + + + + + + + + + +<b>Description:</b> 12.5MM Round Package for Electrolytic Capacitors. Based on Panasonic Electrolytic Capacitors.<br> + + + + + + + + + + + + +>NAME + + + + + + + + +>NAME + + + + + + +<b>Library:</b> MF_Passives<br/> +<b>Description:</b> Symbol for Resistors<br/> + + + + + + + + + + + +>NAME +>VALUE + + +<b>Library:</b> MF_Passives<br/> +<b>Description:</b> Symbol for Non-Polarized Capacitors<br/> + + +>NAME +>VALUE + + + + + + +<b>Library:</b> MF_Passives<br/> +<b>Description:</b> Symbol for Polarized Capacitors<br/> + + + + + + + + + +>NAME +>VALUE + + + + +<b>Library:</b> MF_Passives<br/> +<b>Description:</b> Device for Resistors. Manufacture part number (MPN), Voltage, Tolerance, and Wattage Rating can be added via Attributes. Check https://factory.macrofab.com/parts for the house parts list.<br/> + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +<b>Library:</b> MF_Passives<br/> +<b>Description:</b> Device for Non-Polarized Capacitors. Manufacture part number (MPN) can be added via Attributes. Check https://factory.macrofab.com/parts for the house parts list.<br/> + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +<b>Library:</b> MF_Passives<br/> +<b>Description:</b> Device for Polarized Capacitors. Manufacture part number (MPN), Voltage Rating, and Tolerance can be added via Attributes. Check https://factory.macrofab.com/parts for the house parts list.<br/> + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +<b>Description:</b> Footprint for Single LEDs in 0603<br/> + + + + + + + + + + + + +>NAME + + + + + + + +<b>Description:</b> Footprint for Single LEDs in 0805<br/> + + + + + + + + + + + + +>NAME + + + + + + + + + +<b>Description:</b> Symbol for Single LEDs<br/> + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + + +<b>Library:</b> MF_LEDs<br/> +<b>Description:</b> Device for Single LED Packages. Manufacture part number (MFG#) can be added via Attributes.<br/> + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +<b>Jumpers</b><p> +<author>Created by librarian@cadsoft.de</author> + + +<b>JUMPER</b> + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + + +<b>JUMPER</b> + + + + + + + + + + + + + + + + + + +Generated from <b>polysync_steering_throttle.sch</b><p> +by exp-lbrs.ulp + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +8 +9 +10 +11 +12 +13 +GND +AREF +SDA +SCL +JP1 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +0 +1 +2 +3 +4 +5 +6 +7 +JP2 + + + + + + + + + + + + + + + + + + + + + + + + + + + + +JP3 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +1 +0 +2 +4 +5 +ANALOG +3 +JP4 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +RST +3V3 +5V +GND +Vin +IOREF +NC +JP5 + + + + + + + + + + + + + + + + + + +>NAME +>VALUE +>VALUE + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + + + + + + + + +>NAME +>VALUE + + + + + + + + + + + + +>NAME +>VALUE + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +0 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +