From 9b7123719aad688a98de2af7582b29be681b55b3 Mon Sep 17 00:00:00 2001 From: Austin Morlan Date: Tue, 27 Jun 2017 15:16:45 -0700 Subject: [PATCH 01/84] Add OLED SSD1325 driver library --- platforms/common/libs/gfx/gfx.cpp | 213 +++++++++++++++++ platforms/common/libs/gfx/gfx.h | 73 ++++++ platforms/common/libs/gfx/glcdfont.c | 266 ++++++++++++++++++++++ platforms/common/libs/gfx/license.txt | 24 ++ platforms/common/libs/ssd1325/license.txt | 26 +++ platforms/common/libs/ssd1325/ssd1325.cpp | 231 +++++++++++++++++++ platforms/common/libs/ssd1325/ssd1325.h | 91 ++++++++ 7 files changed, 924 insertions(+) create mode 100755 platforms/common/libs/gfx/gfx.cpp create mode 100755 platforms/common/libs/gfx/gfx.h create mode 100644 platforms/common/libs/gfx/glcdfont.c create mode 100644 platforms/common/libs/gfx/license.txt create mode 100644 platforms/common/libs/ssd1325/license.txt create mode 100644 platforms/common/libs/ssd1325/ssd1325.cpp create mode 100644 platforms/common/libs/ssd1325/ssd1325.h diff --git a/platforms/common/libs/gfx/gfx.cpp b/platforms/common/libs/gfx/gfx.cpp new file mode 100755 index 00000000..ac1bbb01 --- /dev/null +++ b/platforms/common/libs/gfx/gfx.cpp @@ -0,0 +1,213 @@ +/* +This is the core graphics library for all our displays, providing a common +set of graphics primitives (points, lines, circles, etc.). It needs to be +paired with a hardware-specific library for each display device we carry +(to handle the lower-level functions). + +Adafruit invests time and resources providing this open source code, please +support Adafruit & open-source hardware by purchasing products from Adafruit! + +Copyright (c) 2013 Adafruit Industries. All rights reserved. + +Redistribution and use in source and binary forms, with or without +modification, are permitted provided that the following conditions are met: + +- Redistributions of source code must retain the above copyright notice, + this list of conditions and the following disclaimer. +- Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE +LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +POSSIBILITY OF SUCH DAMAGE. + */ + +#include "gfx.h" +#include "glcdfont.c" + + +#ifndef _swap_int16_t +#define _swap_int16_t(a, b) { int16_t t = a; a = b; b = t; } +#endif + + +GFX::GFX(int16_t w, int16_t h): +WIDTH(w), HEIGHT(h) +{ + _width = WIDTH; + _height = HEIGHT; + rotation = 0; + cursor_y = cursor_x = 0; + textsize = 1; + textcolor = textbgcolor = 0xFFFF; + wrap = false; +} + + +void GFX::startWrite(){ + // Overwrite in subclasses if desired! +} + +void GFX::writePixel(int16_t x, int16_t y, uint16_t color){ + // Overwrite in subclasses if startWrite is defined! + drawPixel(x, y, color); +} + +void GFX::endWrite(){ + // Overwrite in subclasses if startWrite is defined! +} + +// TEXT- AND CHARACTER-HANDLING FUNCTIONS ---------------------------------- + +// Draw a character +void GFX::drawChar(int16_t x, int16_t y, unsigned char c, + uint16_t color, uint16_t bg, uint8_t size) { + if((x >= _width) || // Clip right + (y >= _height) || // Clip bottom + ((x + 6 * size - 1) < 0) || // Clip left + ((y + 8 * size - 1) < 0)) // Clip top + return; + + startWrite(); + for(int8_t i=0; i<5; i++ ) { // Char bitmap = 5 columns + uint8_t line = pgm_read_byte(&font[c * 5 + i]); + for(int8_t j=0; j<8; j++, line >>= 1) { + if(line & 1) { + if(size == 1) + writePixel(x+i, y+j, color); + } else if(bg != color) { + if(size == 1) + writePixel(x+i, y+j, bg); + } + } + } + // If opaque, draw vertical line for last column + if(bg != color) { + writeLine(x+5, y, x+5, y+7, bg); + } + endWrite(); +} + +#if ARDUINO >= 100 +size_t GFX::write(uint8_t c) { +#else +void GFX::write(uint8_t c) { +#endif + if(c == '\n') { // Newline? + cursor_x = 0; // Reset x to zero, + cursor_y += textsize * 8; // advance y one line + } else if(c != '\r') { // Ignore carriage returns + if(wrap && ((cursor_x + textsize * 6) > _width)) { // Off right? + cursor_x = 0; // Reset x to zero, + cursor_y += textsize * 8; // advance y one line + } + drawChar(cursor_x, cursor_y, c, textcolor, textbgcolor, textsize); + cursor_x += textsize * 6; // Advance x one char + } +#if ARDUINO >= 100 + return 1; +#endif +} + +void GFX::setCursor(int16_t x, int16_t y) { + cursor_x = x; + cursor_y = y; +} + +int16_t GFX::getCursorX(void) const { + return cursor_x; +} + +int16_t GFX::getCursorY(void) const { + return cursor_y; +} + +void GFX::setTextColor(uint16_t c) { + // For 'transparent' background, we'll set the bg + // to the same as fg instead of using a flag + textcolor = textbgcolor = c; +} + +void GFX::setTextColor(uint16_t c, uint16_t b) { + textcolor = c; + textbgcolor = b; +} + +uint8_t GFX::getRotation(void) const { + return rotation; +} + +void GFX::setRotation(uint8_t x) { + rotation = (x & 3); + switch(rotation) { + case 0: + case 2: + _width = WIDTH; + _height = HEIGHT; + break; + case 1: + case 3: + _width = HEIGHT; + _height = WIDTH; + break; + } +} + +// Return the size of the display (per current rotation) +int16_t GFX::width(void) const { + return _width; +} + +int16_t GFX::height(void) const { + return _height; +} + +// Bresenham's algorithm +void GFX::writeLine(int16_t x0, int16_t y0, int16_t x1, int16_t y1, + uint16_t color) { + int16_t steep = abs(y1 - y0) > abs(x1 - x0); + if (steep) { + _swap_int16_t(x0, y0); + _swap_int16_t(x1, y1); + } + + if (x0 > x1) { + _swap_int16_t(x0, x1); + _swap_int16_t(y0, y1); + } + + int16_t dx, dy; + dx = x1 - x0; + dy = abs(y1 - y0); + + int16_t err = dx / 2; + int16_t ystep; + + if (y0 < y1) { + ystep = 1; + } else { + ystep = -1; + } + + for (; x0<=x1; x0++) { + if (steep) { + writePixel(y0, x0, color); + } else { + writePixel(x0, y0, color); + } + err -= dy; + if (err < 0) { + y0 += ystep; + err += dx; + } + } +} diff --git a/platforms/common/libs/gfx/gfx.h b/platforms/common/libs/gfx/gfx.h new file mode 100755 index 00000000..d970459d --- /dev/null +++ b/platforms/common/libs/gfx/gfx.h @@ -0,0 +1,73 @@ +#ifndef _ADAFRUIT_GFX_H +#define _ADAFRUIT_GFX_H + +#if ARDUINO >= 100 + #include "Arduino.h" + #include "Print.h" +#else + #include "WProgram.h" +#endif + +class GFX : public Print { + + public: + + GFX(int16_t w, int16_t h); // Constructor + + // This MUST be defined by the subclass: + virtual void drawPixel(int16_t x, int16_t y, uint16_t color) = 0; + + // TRANSACTION API / CORE DRAW API + // These MAY be overridden by the subclass to provide device-specific + // optimized code. Otherwise 'generic' versions are used. + virtual void startWrite(void); + virtual void writePixel(int16_t x, int16_t y, uint16_t color); + virtual void endWrite(void); + + // CONTROL API + // These MAY be overridden by the subclass to provide device-specific + // optimized code. Otherwise 'generic' versions are used. + virtual void setRotation(uint8_t r); + + // These exist only with GFX (no subclass overrides) + void + drawChar(int16_t x, int16_t y, unsigned char c, uint16_t color, + uint16_t bg, uint8_t size), + setCursor(int16_t x, int16_t y), + setTextColor(uint16_t c), + setTextColor(uint16_t c, uint16_t bg); + +#if ARDUINO >= 100 + virtual size_t write(uint8_t); +#else + virtual void write(uint8_t); +#endif + + int16_t height(void) const; + int16_t width(void) const; + + uint8_t getRotation(void) const; + + // get current cursor position (get rotation safe maximum values, using: width() for x, height() for y) + int16_t getCursorX(void) const; + int16_t getCursorY(void) const; + + protected: + const int16_t + WIDTH, HEIGHT; // This is the 'raw' display w/h - never changes + int16_t + _width, _height, // Display w/h as modified by current rotation + cursor_x, cursor_y; + uint16_t + textcolor, textbgcolor; + uint8_t + textsize, + rotation; + boolean + wrap; // If set, 'wrap' text at right edge of display + void writeLine(int16_t x0, int16_t y0, int16_t x1, int16_t y1, + uint16_t color); +}; + + +#endif // _ADAFRUIT_GFX_H diff --git a/platforms/common/libs/gfx/glcdfont.c b/platforms/common/libs/gfx/glcdfont.c new file mode 100644 index 00000000..16f26c5d --- /dev/null +++ b/platforms/common/libs/gfx/glcdfont.c @@ -0,0 +1,266 @@ +// This is the 'classic' fixed-space bitmap font for Adafruit_GFX since 1.0. +// See gfxfont.h for newer custom bitmap font info. + +#ifndef FONT5X7_H +#define FONT5X7_H + +// Standard ASCII 5x7 font +static const unsigned char font[] PROGMEM = { + 0x00, 0x00, 0x00, 0x00, 0x00, + 0x3E, 0x5B, 0x4F, 0x5B, 0x3E, + 0x3E, 0x6B, 0x4F, 0x6B, 0x3E, + 0x1C, 0x3E, 0x7C, 0x3E, 0x1C, + 0x18, 0x3C, 0x7E, 0x3C, 0x18, + 0x1C, 0x57, 0x7D, 0x57, 0x1C, + 0x1C, 0x5E, 0x7F, 0x5E, 0x1C, + 0x00, 0x18, 0x3C, 0x18, 0x00, + 0xFF, 0xE7, 0xC3, 0xE7, 0xFF, + 0x00, 0x18, 0x24, 0x18, 0x00, + 0xFF, 0xE7, 0xDB, 0xE7, 0xFF, + 0x30, 0x48, 0x3A, 0x06, 0x0E, + 0x26, 0x29, 0x79, 0x29, 0x26, + 0x40, 0x7F, 0x05, 0x05, 0x07, + 0x40, 0x7F, 0x05, 0x25, 0x3F, + 0x5A, 0x3C, 0xE7, 0x3C, 0x5A, + 0x7F, 0x3E, 0x1C, 0x1C, 0x08, + 0x08, 0x1C, 0x1C, 0x3E, 0x7F, + 0x14, 0x22, 0x7F, 0x22, 0x14, + 0x5F, 0x5F, 0x00, 0x5F, 0x5F, + 0x06, 0x09, 0x7F, 0x01, 0x7F, + 0x00, 0x66, 0x89, 0x95, 0x6A, + 0x60, 0x60, 0x60, 0x60, 0x60, + 0x94, 0xA2, 0xFF, 0xA2, 0x94, + 0x08, 0x04, 0x7E, 0x04, 0x08, + 0x10, 0x20, 0x7E, 0x20, 0x10, + 0x08, 0x08, 0x2A, 0x1C, 0x08, + 0x08, 0x1C, 0x2A, 0x08, 0x08, + 0x1E, 0x10, 0x10, 0x10, 0x10, + 0x0C, 0x1E, 0x0C, 0x1E, 0x0C, + 0x30, 0x38, 0x3E, 0x38, 0x30, + 0x06, 0x0E, 0x3E, 0x0E, 0x06, + 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x5F, 0x00, 0x00, + 0x00, 0x07, 0x00, 0x07, 0x00, + 0x14, 0x7F, 0x14, 0x7F, 0x14, + 0x24, 0x2A, 0x7F, 0x2A, 0x12, + 0x23, 0x13, 0x08, 0x64, 0x62, + 0x36, 0x49, 0x56, 0x20, 0x50, + 0x00, 0x08, 0x07, 0x03, 0x00, + 0x00, 0x1C, 0x22, 0x41, 0x00, + 0x00, 0x41, 0x22, 0x1C, 0x00, + 0x2A, 0x1C, 0x7F, 0x1C, 0x2A, + 0x08, 0x08, 0x3E, 0x08, 0x08, + 0x00, 0x80, 0x70, 0x30, 0x00, + 0x08, 0x08, 0x08, 0x08, 0x08, + 0x00, 0x00, 0x60, 0x60, 0x00, + 0x20, 0x10, 0x08, 0x04, 0x02, + 0x3E, 0x51, 0x49, 0x45, 0x3E, + 0x00, 0x42, 0x7F, 0x40, 0x00, + 0x72, 0x49, 0x49, 0x49, 0x46, + 0x21, 0x41, 0x49, 0x4D, 0x33, + 0x18, 0x14, 0x12, 0x7F, 0x10, + 0x27, 0x45, 0x45, 0x45, 0x39, + 0x3C, 0x4A, 0x49, 0x49, 0x31, + 0x41, 0x21, 0x11, 0x09, 0x07, + 0x36, 0x49, 0x49, 0x49, 0x36, + 0x46, 0x49, 0x49, 0x29, 0x1E, + 0x00, 0x00, 0x14, 0x00, 0x00, + 0x00, 0x40, 0x34, 0x00, 0x00, + 0x00, 0x08, 0x14, 0x22, 0x41, + 0x14, 0x14, 0x14, 0x14, 0x14, + 0x00, 0x41, 0x22, 0x14, 0x08, + 0x02, 0x01, 0x59, 0x09, 0x06, + 0x3E, 0x41, 0x5D, 0x59, 0x4E, + 0x7C, 0x12, 0x11, 0x12, 0x7C, + 0x7F, 0x49, 0x49, 0x49, 0x36, + 0x3E, 0x41, 0x41, 0x41, 0x22, + 0x7F, 0x41, 0x41, 0x41, 0x3E, + 0x7F, 0x49, 0x49, 0x49, 0x41, + 0x7F, 0x09, 0x09, 0x09, 0x01, + 0x3E, 0x41, 0x41, 0x51, 0x73, + 0x7F, 0x08, 0x08, 0x08, 0x7F, + 0x00, 0x41, 0x7F, 0x41, 0x00, + 0x20, 0x40, 0x41, 0x3F, 0x01, + 0x7F, 0x08, 0x14, 0x22, 0x41, + 0x7F, 0x40, 0x40, 0x40, 0x40, + 0x7F, 0x02, 0x1C, 0x02, 0x7F, + 0x7F, 0x04, 0x08, 0x10, 0x7F, + 0x3E, 0x41, 0x41, 0x41, 0x3E, + 0x7F, 0x09, 0x09, 0x09, 0x06, + 0x3E, 0x41, 0x51, 0x21, 0x5E, + 0x7F, 0x09, 0x19, 0x29, 0x46, + 0x26, 0x49, 0x49, 0x49, 0x32, + 0x03, 0x01, 0x7F, 0x01, 0x03, + 0x3F, 0x40, 0x40, 0x40, 0x3F, + 0x1F, 0x20, 0x40, 0x20, 0x1F, + 0x3F, 0x40, 0x38, 0x40, 0x3F, + 0x63, 0x14, 0x08, 0x14, 0x63, + 0x03, 0x04, 0x78, 0x04, 0x03, + 0x61, 0x59, 0x49, 0x4D, 0x43, + 0x00, 0x7F, 0x41, 0x41, 0x41, + 0x02, 0x04, 0x08, 0x10, 0x20, + 0x00, 0x41, 0x41, 0x41, 0x7F, + 0x04, 0x02, 0x01, 0x02, 0x04, + 0x40, 0x40, 0x40, 0x40, 0x40, + 0x00, 0x03, 0x07, 0x08, 0x00, + 0x20, 0x54, 0x54, 0x78, 0x40, + 0x7F, 0x28, 0x44, 0x44, 0x38, + 0x38, 0x44, 0x44, 0x44, 0x28, + 0x38, 0x44, 0x44, 0x28, 0x7F, + 0x38, 0x54, 0x54, 0x54, 0x18, + 0x00, 0x08, 0x7E, 0x09, 0x02, + 0x18, 0xA4, 0xA4, 0x9C, 0x78, + 0x7F, 0x08, 0x04, 0x04, 0x78, + 0x00, 0x44, 0x7D, 0x40, 0x00, + 0x20, 0x40, 0x40, 0x3D, 0x00, + 0x7F, 0x10, 0x28, 0x44, 0x00, + 0x00, 0x41, 0x7F, 0x40, 0x00, + 0x7C, 0x04, 0x78, 0x04, 0x78, + 0x7C, 0x08, 0x04, 0x04, 0x78, + 0x38, 0x44, 0x44, 0x44, 0x38, + 0xFC, 0x18, 0x24, 0x24, 0x18, + 0x18, 0x24, 0x24, 0x18, 0xFC, + 0x7C, 0x08, 0x04, 0x04, 0x08, + 0x48, 0x54, 0x54, 0x54, 0x24, + 0x04, 0x04, 0x3F, 0x44, 0x24, + 0x3C, 0x40, 0x40, 0x20, 0x7C, + 0x1C, 0x20, 0x40, 0x20, 0x1C, + 0x3C, 0x40, 0x30, 0x40, 0x3C, + 0x44, 0x28, 0x10, 0x28, 0x44, + 0x4C, 0x90, 0x90, 0x90, 0x7C, + 0x44, 0x64, 0x54, 0x4C, 0x44, + 0x00, 0x08, 0x36, 0x41, 0x00, + 0x00, 0x00, 0x77, 0x00, 0x00, + 0x00, 0x41, 0x36, 0x08, 0x00, + 0x02, 0x01, 0x02, 0x04, 0x02, + 0x3C, 0x26, 0x23, 0x26, 0x3C, + 0x1E, 0xA1, 0xA1, 0x61, 0x12, + 0x3A, 0x40, 0x40, 0x20, 0x7A, + 0x38, 0x54, 0x54, 0x55, 0x59, + 0x21, 0x55, 0x55, 0x79, 0x41, + 0x22, 0x54, 0x54, 0x78, 0x42, // a-umlaut + 0x21, 0x55, 0x54, 0x78, 0x40, + 0x20, 0x54, 0x55, 0x79, 0x40, + 0x0C, 0x1E, 0x52, 0x72, 0x12, + 0x39, 0x55, 0x55, 0x55, 0x59, + 0x39, 0x54, 0x54, 0x54, 0x59, + 0x39, 0x55, 0x54, 0x54, 0x58, + 0x00, 0x00, 0x45, 0x7C, 0x41, + 0x00, 0x02, 0x45, 0x7D, 0x42, + 0x00, 0x01, 0x45, 0x7C, 0x40, + 0x7D, 0x12, 0x11, 0x12, 0x7D, // A-umlaut + 0xF0, 0x28, 0x25, 0x28, 0xF0, + 0x7C, 0x54, 0x55, 0x45, 0x00, + 0x20, 0x54, 0x54, 0x7C, 0x54, + 0x7C, 0x0A, 0x09, 0x7F, 0x49, + 0x32, 0x49, 0x49, 0x49, 0x32, + 0x3A, 0x44, 0x44, 0x44, 0x3A, // o-umlaut + 0x32, 0x4A, 0x48, 0x48, 0x30, + 0x3A, 0x41, 0x41, 0x21, 0x7A, + 0x3A, 0x42, 0x40, 0x20, 0x78, + 0x00, 0x9D, 0xA0, 0xA0, 0x7D, + 0x3D, 0x42, 0x42, 0x42, 0x3D, // O-umlaut + 0x3D, 0x40, 0x40, 0x40, 0x3D, + 0x3C, 0x24, 0xFF, 0x24, 0x24, + 0x48, 0x7E, 0x49, 0x43, 0x66, + 0x2B, 0x2F, 0xFC, 0x2F, 0x2B, + 0xFF, 0x09, 0x29, 0xF6, 0x20, + 0xC0, 0x88, 0x7E, 0x09, 0x03, + 0x20, 0x54, 0x54, 0x79, 0x41, + 0x00, 0x00, 0x44, 0x7D, 0x41, + 0x30, 0x48, 0x48, 0x4A, 0x32, + 0x38, 0x40, 0x40, 0x22, 0x7A, + 0x00, 0x7A, 0x0A, 0x0A, 0x72, + 0x7D, 0x0D, 0x19, 0x31, 0x7D, + 0x26, 0x29, 0x29, 0x2F, 0x28, + 0x26, 0x29, 0x29, 0x29, 0x26, + 0x30, 0x48, 0x4D, 0x40, 0x20, + 0x38, 0x08, 0x08, 0x08, 0x08, + 0x08, 0x08, 0x08, 0x08, 0x38, + 0x2F, 0x10, 0xC8, 0xAC, 0xBA, + 0x2F, 0x10, 0x28, 0x34, 0xFA, + 0x00, 0x00, 0x7B, 0x00, 0x00, + 0x08, 0x14, 0x2A, 0x14, 0x22, + 0x22, 0x14, 0x2A, 0x14, 0x08, + 0x55, 0x00, 0x55, 0x00, 0x55, // #176 (25% block) missing in old code + 0xAA, 0x55, 0xAA, 0x55, 0xAA, // 50% block + 0xFF, 0x55, 0xFF, 0x55, 0xFF, // 75% block + 0x00, 0x00, 0x00, 0xFF, 0x00, + 0x10, 0x10, 0x10, 0xFF, 0x00, + 0x14, 0x14, 0x14, 0xFF, 0x00, + 0x10, 0x10, 0xFF, 0x00, 0xFF, + 0x10, 0x10, 0xF0, 0x10, 0xF0, + 0x14, 0x14, 0x14, 0xFC, 0x00, + 0x14, 0x14, 0xF7, 0x00, 0xFF, + 0x00, 0x00, 0xFF, 0x00, 0xFF, + 0x14, 0x14, 0xF4, 0x04, 0xFC, + 0x14, 0x14, 0x17, 0x10, 0x1F, + 0x10, 0x10, 0x1F, 0x10, 0x1F, + 0x14, 0x14, 0x14, 0x1F, 0x00, + 0x10, 0x10, 0x10, 0xF0, 0x00, + 0x00, 0x00, 0x00, 0x1F, 0x10, + 0x10, 0x10, 0x10, 0x1F, 0x10, + 0x10, 0x10, 0x10, 0xF0, 0x10, + 0x00, 0x00, 0x00, 0xFF, 0x10, + 0x10, 0x10, 0x10, 0x10, 0x10, + 0x10, 0x10, 0x10, 0xFF, 0x10, + 0x00, 0x00, 0x00, 0xFF, 0x14, + 0x00, 0x00, 0xFF, 0x00, 0xFF, + 0x00, 0x00, 0x1F, 0x10, 0x17, + 0x00, 0x00, 0xFC, 0x04, 0xF4, + 0x14, 0x14, 0x17, 0x10, 0x17, + 0x14, 0x14, 0xF4, 0x04, 0xF4, + 0x00, 0x00, 0xFF, 0x00, 0xF7, + 0x14, 0x14, 0x14, 0x14, 0x14, + 0x14, 0x14, 0xF7, 0x00, 0xF7, + 0x14, 0x14, 0x14, 0x17, 0x14, + 0x10, 0x10, 0x1F, 0x10, 0x1F, + 0x14, 0x14, 0x14, 0xF4, 0x14, + 0x10, 0x10, 0xF0, 0x10, 0xF0, + 0x00, 0x00, 0x1F, 0x10, 0x1F, + 0x00, 0x00, 0x00, 0x1F, 0x14, + 0x00, 0x00, 0x00, 0xFC, 0x14, + 0x00, 0x00, 0xF0, 0x10, 0xF0, + 0x10, 0x10, 0xFF, 0x10, 0xFF, + 0x14, 0x14, 0x14, 0xFF, 0x14, + 0x10, 0x10, 0x10, 0x1F, 0x00, + 0x00, 0x00, 0x00, 0xF0, 0x10, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xF0, 0xF0, 0xF0, 0xF0, 0xF0, + 0xFF, 0xFF, 0xFF, 0x00, 0x00, + 0x00, 0x00, 0x00, 0xFF, 0xFF, + 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, + 0x38, 0x44, 0x44, 0x38, 0x44, + 0xFC, 0x4A, 0x4A, 0x4A, 0x34, // sharp-s or beta + 0x7E, 0x02, 0x02, 0x06, 0x06, + 0x02, 0x7E, 0x02, 0x7E, 0x02, + 0x63, 0x55, 0x49, 0x41, 0x63, + 0x38, 0x44, 0x44, 0x3C, 0x04, + 0x40, 0x7E, 0x20, 0x1E, 0x20, + 0x06, 0x02, 0x7E, 0x02, 0x02, + 0x99, 0xA5, 0xE7, 0xA5, 0x99, + 0x1C, 0x2A, 0x49, 0x2A, 0x1C, + 0x4C, 0x72, 0x01, 0x72, 0x4C, + 0x30, 0x4A, 0x4D, 0x4D, 0x30, + 0x30, 0x48, 0x78, 0x48, 0x30, + 0xBC, 0x62, 0x5A, 0x46, 0x3D, + 0x3E, 0x49, 0x49, 0x49, 0x00, + 0x7E, 0x01, 0x01, 0x01, 0x7E, + 0x2A, 0x2A, 0x2A, 0x2A, 0x2A, + 0x44, 0x44, 0x5F, 0x44, 0x44, + 0x40, 0x51, 0x4A, 0x44, 0x40, + 0x40, 0x44, 0x4A, 0x51, 0x40, + 0x00, 0x00, 0xFF, 0x01, 0x03, + 0xE0, 0x80, 0xFF, 0x00, 0x00, + 0x08, 0x08, 0x6B, 0x6B, 0x08, + 0x36, 0x12, 0x36, 0x24, 0x36, + 0x06, 0x0F, 0x09, 0x0F, 0x06, + 0x00, 0x00, 0x18, 0x18, 0x00, + 0x00, 0x00, 0x10, 0x10, 0x00, + 0x30, 0x40, 0xFF, 0x01, 0x01, + 0x00, 0x1F, 0x01, 0x01, 0x1E, + 0x00, 0x19, 0x1D, 0x17, 0x12, + 0x00, 0x3C, 0x3C, 0x3C, 0x3C, + 0x00, 0x00, 0x00, 0x00, 0x00 // #255 NBSP +}; +#endif // FONT5X7_H diff --git a/platforms/common/libs/gfx/license.txt b/platforms/common/libs/gfx/license.txt new file mode 100644 index 00000000..7492e93a --- /dev/null +++ b/platforms/common/libs/gfx/license.txt @@ -0,0 +1,24 @@ +Software License Agreement (BSD License) + +Copyright (c) 2012 Adafruit Industries. All rights reserved. + +Redistribution and use in source and binary forms, with or without +modification, are permitted provided that the following conditions are met: + +- Redistributions of source code must retain the above copyright notice, + this list of conditions and the following disclaimer. +- Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE +LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +POSSIBILITY OF SUCH DAMAGE. diff --git a/platforms/common/libs/ssd1325/license.txt b/platforms/common/libs/ssd1325/license.txt new file mode 100644 index 00000000..0652a4aa --- /dev/null +++ b/platforms/common/libs/ssd1325/license.txt @@ -0,0 +1,26 @@ +Software License Agreement (BSD License) + +Copyright (c) 2015, Adafruit Industries +All rights reserved. + +Redistribution and use in source and binary forms, with or without +modification, are permitted provided that the following conditions are met: +1. Redistributions of source code must retain the above copyright +notice, this list of conditions and the following disclaimer. +2. Redistributions in binary form must reproduce the above copyright +notice, this list of conditions and the following disclaimer in the +documentation and/or other materials provided with the distribution. +3. Neither the name of the copyright holders nor the +names of its contributors may be used to endorse or promote products +derived from this software without specific prior written permission. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS ''AS IS'' AND ANY +EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED +WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY +DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +(INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +(INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. diff --git a/platforms/common/libs/ssd1325/ssd1325.cpp b/platforms/common/libs/ssd1325/ssd1325.cpp new file mode 100644 index 00000000..3c9554bc --- /dev/null +++ b/platforms/common/libs/ssd1325/ssd1325.cpp @@ -0,0 +1,231 @@ +/********************************************************************* +This is a library for our Monochrome OLEDs based on SSD1325 drivers + + Pick one up today in the adafruit shop! + ------> http://www.adafruit.com/category/63_98 + +These displays use SPI to communicate, 4 or 5 pins are required to +interface + +Adafruit invests time and resources providing this open source code, +please support Adafruit and open-source hardware by purchasing +products from Adafruit! + +Written by Limor Fried/Ladyada for Adafruit Industries. +BSD license, check license.txt for more information +All text above, and the splash screen below must be included in any redistribution +*********************************************************************/ + +#include +#include +#include "gfx.h" +#include "glcdfont.c" +#include "ssd1325.h" + +// a 5x7 font table +extern const uint8_t PROGMEM font[]; + +// buffer at startup contains logo +static uint8_t buffer[SSD1325_LCDHEIGHT * SSD1325_LCDWIDTH / 8] = { +0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, +0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, +0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, +0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, +0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, +0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, +0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, +0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, +0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x80, 0xc0, 0xe0, 0xe0, 0xf0, 0xf8, 0xf8, 0xf8, 0xfc, 0xfc, +0xfc, 0xfe, 0xfe, 0xfe, 0xfe, 0xfe, 0xfe, 0xfe, 0xfe, 0xfe, 0xfe, 0xfe, 0xfe, 0xfe, 0xfe, 0xfe, +0xfe, 0xfe, 0xfe, 0xfe, 0xfe, 0xfe, 0xfe, 0xfe, 0xfe, 0xfe, 0xfe, 0xfe, 0xfe, 0xfe, 0xfe, 0xfe, +0xfe, 0xfe, 0xfe, 0xfe, 0xfe, 0xfe, 0xfe, 0xfe, 0xfe, 0xfe, 0xfe, 0xfe, 0xfe, 0xfe, 0xfe, 0xfe, +0xfe, 0xfe, 0xfe, 0xfe, 0xfe, 0xfe, 0xfe, 0xfe, 0xfe, 0xfe, 0xfe, 0xfe, 0xfe, 0xfe, 0xfe, 0xfe, +0xfe, 0xfe, 0xfe, 0xfe, 0xfe, 0xfe, 0xfe, 0xfe, 0xfe, 0xfe, 0xfe, 0xfe, 0xfe, 0xfe, 0xfe, 0xfe, +0xfe, 0xfe, 0xfe, 0xfe, 0xfe, 0xfe, 0xfe, 0xfe, 0xfe, 0xfe, 0xfe, 0xfe, 0xfe, 0xfe, 0xfe, 0xfc, +0xfc, 0xfc, 0xf8, 0xf8, 0xf8, 0xf0, 0xe0, 0xe0, 0xc0, 0x80, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, +0x00, 0x80, 0xf0, 0xf8, 0xfe, 0xff, 0xff, 0xff, 0xff, 0xff, 0x7f, 0x3f, 0xdf, 0x6f, 0x27, 0xb3, +0xdb, 0x4b, 0x69, 0x2d, 0x25, 0xa5, 0xa5, 0xa5, 0x2d, 0x6d, 0x49, 0xdb, 0x93, 0x37, 0x67, 0xcf, +0x9f, 0x3f, 0x7f, 0xff, 0xff, 0xff, 0xff, 0xff, 0x3f, 0xcf, 0x67, 0x33, 0x9b, 0xdb, 0x49, 0x6d, +0x2d, 0x25, 0x25, 0x25, 0x25, 0x25, 0x6d, 0x6d, 0x49, 0xdb, 0x9b, 0xb3, 0xa7, 0xef, 0xef, 0xff, +0xff, 0xff, 0xff, 0x7f, 0x3f, 0x9f, 0xcf, 0x67, 0xb3, 0x9b, 0xdb, 0x49, 0x6d, 0x25, 0xa5, 0xa5, +0xa5, 0x25, 0x2d, 0x69, 0x4b, 0xdb, 0xb3, 0x27, 0x4f, 0xdf, 0xbf, 0xff, 0xff, 0xff, 0xff, 0x7f, +0x3f, 0xdf, 0x4f, 0x27, 0xb3, 0xdb, 0x4b, 0x49, 0x2d, 0x25, 0xa5, 0xa5, 0xa5, 0x25, 0x6d, 0x49, +0xdb, 0xdb, 0xb3, 0x27, 0x4f, 0x9f, 0xbf, 0xff, 0xff, 0xff, 0xff, 0xfe, 0xf8, 0xf0, 0xc0, 0x00, +0xfc, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0x03, 0xf8, 0x3e, 0x03, 0xf8, 0x0e, 0xe3, 0xf9, +0xfc, 0xfe, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfe, 0xfc, 0xf1, 0x07, 0x3c, +0xf1, 0x07, 0xfc, 0xe1, 0x0f, 0xff, 0xff, 0xf0, 0xc0, 0x3f, 0x60, 0xcf, 0x9f, 0xb0, 0x26, 0x2f, +0x6f, 0x6f, 0x6f, 0x6f, 0x6f, 0x6f, 0x6f, 0x4f, 0xcf, 0xde, 0x9e, 0x3f, 0x7f, 0xff, 0xff, 0xff, +0xff, 0x0f, 0xe1, 0xfc, 0x07, 0xf1, 0x1c, 0x07, 0xf1, 0xfc, 0xfe, 0xff, 0xff, 0xff, 0xff, 0xff, +0xff, 0xff, 0xff, 0xff, 0xfe, 0xfc, 0xfd, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0x07, 0xe1, 0xfe, +0x07, 0xf9, 0x1c, 0x07, 0xf9, 0xfc, 0xfe, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, +0xfe, 0xfc, 0xfd, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfc, +0x1f, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xf0, 0xc7, 0x1e, 0x70, 0xc7, 0x9c, 0x71, 0x47, +0x9f, 0xbf, 0x3f, 0x7f, 0x7f, 0x7f, 0x7f, 0x7f, 0x7f, 0x7f, 0x3f, 0x9f, 0xcf, 0x63, 0x30, 0x8e, +0xe3, 0x38, 0x9f, 0xc1, 0xf8, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfe, 0xbc, 0xbc, 0x3d, 0x79, 0x79, +0x7b, 0x7b, 0x7b, 0x7b, 0x7b, 0x7b, 0x7b, 0x32, 0x86, 0xfc, 0x39, 0x03, 0xfe, 0x00, 0x87, 0xff, +0xff, 0xf8, 0xc3, 0x9f, 0x70, 0xc3, 0x9e, 0x30, 0x67, 0xcf, 0x9f, 0x3f, 0x7f, 0x7f, 0x7f, 0x7f, +0x7f, 0x7f, 0x7f, 0x3f, 0xbf, 0xdf, 0x5f, 0x3f, 0xbf, 0xff, 0xff, 0xff, 0xff, 0xf0, 0xc3, 0x1f, +0x70, 0xc7, 0x9e, 0x30, 0x67, 0xcf, 0xbf, 0x3f, 0x7f, 0x7f, 0x7f, 0x7f, 0x7f, 0x7f, 0x7f, 0x3f, +0x9f, 0xcf, 0x7f, 0x3f, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0x1f, +0x00, 0x00, 0x07, 0x0f, 0x3f, 0x7f, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfe, 0xfc, 0xf9, 0xf3, 0xf6, +0xe4, 0xed, 0xed, 0xc9, 0xcb, 0xcb, 0xcb, 0xcb, 0xcb, 0xe9, 0xed, 0xe4, 0xf6, 0xf2, 0xfb, 0xfd, +0xfc, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xf9, 0xf2, 0xf6, 0xe4, 0xed, 0xc9, 0xc9, 0xdb, +0xdb, 0xda, 0xda, 0xda, 0xda, 0xdb, 0xdb, 0xc9, 0xed, 0xe4, 0xf6, 0xf3, 0xf9, 0xfe, 0xff, 0xff, +0xff, 0xff, 0xff, 0xff, 0xfe, 0xfc, 0xf9, 0xfb, 0xf2, 0xe6, 0xec, 0xed, 0xe9, 0xcb, 0xcb, 0xcb, +0xcb, 0xcb, 0xc9, 0xed, 0xed, 0xe4, 0xf2, 0xf3, 0xf9, 0xfc, 0xfe, 0xff, 0xff, 0xff, 0xff, 0xff, +0xfe, 0xfc, 0xf9, 0xfb, 0xf2, 0xe4, 0xed, 0xed, 0xc9, 0xcb, 0xcb, 0xcb, 0xcb, 0xcb, 0xc9, 0xed, +0xed, 0xe4, 0xf2, 0xfb, 0xf9, 0xfc, 0xfe, 0xff, 0xff, 0xff, 0x7f, 0x3f, 0x0f, 0x07, 0x01, 0x00, +0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x03, 0x03, 0x07, 0x07, 0x0f, 0x0f, 0x1f, 0x1f, +0x1f, 0x3f, 0x3f, 0x3f, 0x3f, 0x3f, 0x3f, 0x3f, 0x3f, 0x3f, 0x3f, 0x3f, 0x3f, 0x3f, 0x3f, 0x3f, +0x3f, 0x3f, 0x3f, 0x3f, 0x3f, 0x3f, 0x3f, 0x3f, 0x3f, 0x3f, 0x3f, 0x3f, 0x3f, 0x3f, 0x3f, 0x3f, +0x3f, 0x3f, 0x3f, 0x3f, 0x3f, 0x3f, 0x3f, 0x3f, 0x3f, 0x3f, 0x3f, 0x3f, 0x3f, 0x3f, 0x3f, 0x3f, +0x3f, 0x3f, 0x3f, 0x3f, 0x3f, 0x3f, 0x3f, 0x3f, 0x3f, 0x3f, 0x3f, 0x3f, 0x3f, 0x3f, 0x3f, 0x3f, +0x3f, 0x3f, 0x3f, 0x3f, 0x3f, 0x3f, 0x3f, 0x3f, 0x3f, 0x3f, 0x3f, 0x3f, 0x3f, 0x3f, 0x3f, 0x3f, +0x3f, 0x3f, 0x3f, 0x3f, 0x3f, 0x3f, 0x3f, 0x3f, 0x3f, 0x3f, 0x3f, 0x3f, 0x3f, 0x3f, 0x3f, 0x1f, +0x1f, 0x1f, 0x0f, 0x0f, 0x0f, 0x07, 0x03, 0x03, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, +0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, +0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, +0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, +0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, +0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, +0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, +0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, +0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, +}; + + +void SSD1325::begin(void) { + SPI.begin(); + SPI.setDataMode(SPI_MODE0); + SPI.setClockDivider(SPI_CLOCK_DIV2); + + pinMode(dc, OUTPUT); + pinMode(rst, OUTPUT); + pinMode(cs, OUTPUT); + + digitalWrite(rst, HIGH); + // VDD (3.3V) goes high at start, lets just chill for a ms + delay(1); + // bring reset low + digitalWrite(rst, LOW); + // wait 10ms + delay(10); + // bring out of reset + digitalWrite(rst, HIGH); + + delay(500); + + sendCommand(SSD1325_DISPLAYOFF); /* display off */ + sendCommand(SSD1325_SETCLOCK); /* set osc division */ + sendCommand(0xF1); /* 145 */ + sendCommand(SSD1325_SETMULTIPLEX ); /* multiplex ratio */ + sendCommand(0x3f); /* duty = 1/64 */ + sendCommand( SSD1325_SETOFFSET); /* set display offset --- */ + sendCommand(0x4C); /* 76 */ + sendCommand(SSD1325_SETSTARTLINE); /*set start line */ + sendCommand(0x00); /* ------ */ + sendCommand(SSD1325_MASTERCONFIG); /*Set Master Config DC/DC Converter*/ + sendCommand(0x02); + sendCommand(SSD1325_SETREMAP); /* set segment remap------ */ + sendCommand(0x56); + sendCommand(SSD1325_SETCURRENT + 0x1); /* Set Current Range */ + sendCommand(SSD1325_SETGRAYTABLE); + sendCommand(0x01); + sendCommand(0x11); + sendCommand(0x22); + sendCommand(0x32); + sendCommand(0x43); + sendCommand(0x54); + sendCommand(0x65); + sendCommand(0x76); + sendCommand(SSD1325_SETCONTRAST); /* set contrast current */ + sendCommand(0x7F); // max! + sendCommand(SSD1325_SETROWPERIOD); + sendCommand(0x51); + sendCommand(SSD1325_SETPHASELEN); + sendCommand(0x55); + sendCommand(SSD1325_SETPRECHARGECOMP); + sendCommand(0x02); + sendCommand(SSD1325_SETPRECHARGECOMPENABLE); + sendCommand(0x28); + sendCommand(SSD1325_SETVCOMLEVEL); // Set High Voltage Level of COM Pin + sendCommand(0x1C); //? + sendCommand(SSD1325_SETVSL); // set Low Voltage Level of SEG Pin + sendCommand(0x0D|0x02); + + sendCommand(SSD1325_NORMALDISPLAY); /* set display mode */ + + sendCommand(SSD1325_DISPLAYON); /* display ON */ +} + + +void SSD1325::sendBuffer(void) { + sendCommand(0x15); /* set column address */ + sendCommand(0x00); /* set column start address */ + sendCommand(0x3f); /* set column end address */ + sendCommand(0x75); /* set row address */ + sendCommand(0x00); /* set row start address */ + sendCommand(0x3f); /* set row end address */ + delay(1); + + for (uint16_t x=0; x<128; x+=2) { + for (uint16_t y=0; y<64; y+=8) { // we write 8 pixels at once + uint8_t left8 = buffer[y*16+x]; + uint8_t right8 = buffer[y*16+x+1]; + for (uint8_t p=0; p<8; p++) { + uint8_t d = 0; + if (left8 & (1 << p)) d |= 0xF0; + if (right8 & (1 << p)) d |= 0x0F; + sendData(d); + } + } + } +} + + +void SSD1325::eraseBuffer(void) { + memset(buffer, 0, sizeof(buffer)); +} + + +void SSD1325::sendCommand(uint8_t c) { + digitalWrite(dc, LOW); + digitalWrite(cs, LOW); + SPI.transfer(c); + digitalWrite(cs, HIGH); +} + +void SSD1325::sendData(uint8_t c) { + digitalWrite(dc, HIGH); + digitalWrite(cs, LOW); + SPI.transfer(c); + digitalWrite(cs, HIGH); +} + + +void SSD1325::drawPixel(int16_t x, int16_t y, uint16_t color) { + if ((x >= width()) || (y >= height()) || (x < 0) || (y < 0)) + return; + + // check rotation, move pixel around if necessary + switch (getRotation()) { + case 1: + adagfx_swap(x, y); + x = WIDTH - x - 1; + break; + case 2: + x = WIDTH - x - 1; + y = HEIGHT - y - 1; + break; + case 3: + adagfx_swap(x, y); + y = HEIGHT - y - 1; + break; + } + + // x is which column + if (color == WHITE) + buffer[x+ (y/8)*SSD1325_LCDWIDTH] |= _BV((y%8)); + else + buffer[x+ (y/8)*SSD1325_LCDWIDTH] &= ~_BV((y%8)); +} diff --git a/platforms/common/libs/ssd1325/ssd1325.h b/platforms/common/libs/ssd1325/ssd1325.h new file mode 100644 index 00000000..1ca57209 --- /dev/null +++ b/platforms/common/libs/ssd1325/ssd1325.h @@ -0,0 +1,91 @@ +/********************************************************************* +This is a library for our Monochrome OLEDs based on SSD1325 drivers + + Pick one up today in the adafruit shop! + ------> http://www.adafruit.com/category/63_98 + +These sendBuffers use SPI to communicate, 4 or 5 pins are required to +interface + +Adafruit invests time and resources providing this open source code, +please support Adafruit and open-source hardware by purchasing +products from Adafruit! + +Written by Limor Fried/Ladyada for Adafruit Industries. +BSD license, check license.txt for more information +All text above, and the splash screen must be included in any redistribution +*********************************************************************/ + + +#if ARDUINO >= 100 + #include "Arduino.h" +#else + #include "WProgram.h" +#endif + +#ifdef __arm__ +#define _BV(b) (1<<(b)) +#endif + +#include "gfx.h" + +#ifndef adagfx_swap +#define adagfx_swap(a, b) { uint8_t t = a; a = b; b = t; } +#endif + +#define BLACK 0 +#define WHITE 1 + +#define SSD1325_LCDWIDTH 128 +#define SSD1325_LCDHEIGHT 64 + +#define SSD1325_SETCOLADDR 0x15 +#define SSD1325_SETROWADDR 0x75 +#define SSD1325_SETCONTRAST 0x81 +#define SSD1325_SETCURRENT 0x84 + +#define SSD1325_SETREMAP 0xA0 +#define SSD1325_SETSTARTLINE 0xA1 +#define SSD1325_SETOFFSET 0xA2 +#define SSD1325_NORMALDISPLAY 0xA4 +#define SSD1325_DISPLAYALLON 0xA5 +#define SSD1325_DISPLAYALLOFF 0xA6 +#define SSD1325_INVERTDISPLAY 0xA7 +#define SSD1325_SETMULTIPLEX 0xA8 +#define SSD1325_MASTERCONFIG 0xAD +#define SSD1325_DISPLAYOFF 0xAE +#define SSD1325_DISPLAYON 0xAF + +#define SSD1325_SETPRECHARGECOMPENABLE 0xB0 +#define SSD1325_SETPHASELEN 0xB1 +#define SSD1325_SETROWPERIOD 0xB2 +#define SSD1325_SETCLOCK 0xB3 +#define SSD1325_SETPRECHARGECOMP 0xB4 +#define SSD1325_SETGRAYTABLE 0xB8 +#define SSD1325_SETPRECHARGEVOLTAGE 0xBC +#define SSD1325_SETVCOMLEVEL 0xBE +#define SSD1325_SETVSL 0xBF + +#define SSD1325_GFXACCEL 0x23 +#define SSD1325_DRAWRECT 0x24 +#define SSD1325_COPY 0x25 + +class SSD1325 : public GFX { + public: + SSD1325(int8_t SID, int8_t SCLK, int8_t DC, int8_t RST, int8_t CS) : GFX(128,64), sid(SID), sclk(SCLK), dc(DC), rst(RST), cs(CS) {} + + void begin(void); + void eraseBuffer(void); + void sendBuffer(); + + private: + int8_t sid; + int8_t sclk; + int8_t dc; + int8_t rst; + int8_t cs; + + void sendCommand(uint8_t c); + void sendData(uint8_t c); + void drawPixel(int16_t x, int16_t y, uint16_t color); +}; From 5809e003ff5a0ae8ba7e872eda3390c6273112e8 Mon Sep 17 00:00:00 2001 From: Austin Morlan Date: Tue, 27 Jun 2017 17:19:22 -0700 Subject: [PATCH 02/84] Add initial display logic --- .../firmware/can_gateway/CMakeLists.txt | 9 +- .../firmware/can_gateway/include/display.h | 121 +++++++++++++ .../firmware/can_gateway/include/globals.h | 48 ++++++ .../can_gateway/src/communications.cpp | 87 ++++++++++ .../firmware/can_gateway/src/display.cpp | 159 ++++++++++++++++++ .../firmware/can_gateway/src/init.cpp | 8 + .../firmware/can_gateway/src/main.cpp | 5 +- 7 files changed, 434 insertions(+), 3 deletions(-) create mode 100644 platforms/kia_soul/firmware/can_gateway/include/display.h create mode 100644 platforms/kia_soul/firmware/can_gateway/src/display.cpp diff --git a/platforms/kia_soul/firmware/can_gateway/CMakeLists.txt b/platforms/kia_soul/firmware/can_gateway/CMakeLists.txt index bcea5d0b..0e7a42b4 100644 --- a/platforms/kia_soul/firmware/can_gateway/CMakeLists.txt +++ b/platforms/kia_soul/firmware/can_gateway/CMakeLists.txt @@ -22,10 +22,13 @@ generate_arduino_firmware( ${CMAKE_SOURCE_DIR}/common/libs/serial/oscc_serial.cpp ${CMAKE_SOURCE_DIR}/common/libs/can/oscc_can.cpp ${CMAKE_SOURCE_DIR}/common/libs/time/oscc_time.cpp + ${CMAKE_SOURCE_DIR}/common/libs/ssd1325/ssd1325.cpp + ${CMAKE_SOURCE_DIR}/common/libs/gfx/gfx.cpp src/main.cpp src/globals.cpp src/init.cpp - src/communications.cpp) + src/communications.cpp + src/display.cpp) target_include_directories( kia-soul-can-gateway @@ -36,4 +39,6 @@ target_include_directories( ${CMAKE_SOURCE_DIR}/common/libs/mcp_can ${CMAKE_SOURCE_DIR}/common/libs/serial ${CMAKE_SOURCE_DIR}/common/libs/can - ${CMAKE_SOURCE_DIR}/common/libs/time) + ${CMAKE_SOURCE_DIR}/common/libs/time + ${CMAKE_SOURCE_DIR}/common/libs/ssd1325 + ${CMAKE_SOURCE_DIR}/common/libs/gfx) diff --git a/platforms/kia_soul/firmware/can_gateway/include/display.h b/platforms/kia_soul/firmware/can_gateway/include/display.h new file mode 100644 index 00000000..9b46820f --- /dev/null +++ b/platforms/kia_soul/firmware/can_gateway/include/display.h @@ -0,0 +1,121 @@ +/** + * @file display.h + * @brief Display functionality. + * + */ + + +#ifndef _OSCC_KIA_SOUL_CAN_GATEWAY_DISPLAY_H_ +#define _OSCC_KIA_SOUL_CAN_GATEWAY_DISPLAY_H_ + + +/** + * @brief Enumeration of possible screens. + * + */ +typedef enum +{ + STATUS_SCREEN, + ERROR_SCREEN, + SCREEN_COUNT +} screen_t; + + +/** + * @brief Enumeration of possible status pages. + * + */ +typedef enum +{ + STATUS_PAGE_MAIN, + STATUS_PAGE_COUNT +} status_page_t; + + +/** + * @brief Enumeration of possible error pages. + * + */ +typedef enum +{ + ERROR_PAGE_MAIN, + ERROR_PAGE_COUNT +} error_page_t; + + +/** + * @brief Enumeration of possible gateway statuses. + * + */ +typedef enum +{ + GATEWAY_STATUS_UNKNOWN, + GATEWAY_STATUS_GOOD, + GATEWAY_STATUS_WARNING, + GATEWAY_STATUS_ERROR +} gateway_status_t; + + +/** + * @brief Enumeration of possible module statuses. + * + */ +typedef enum +{ + MODULE_STATUS_UNKNOWN, + MODULE_STATUS_ENABLED, + MODULE_STATUS_DISABLED, + MODULE_STATUS_ERROR, +} module_status_t; + + +/** + * @brief Current status screen state. + * + */ +typedef struct +{ + status_page_t current_page; + gateway_status_t gateway_status; + module_status_t brake_status; + module_status_t steering_status; + module_status_t throttle_status; +} status_screen_s; + + +/** + * @brief Current error screen state. + * + */ +typedef struct +{ + error_page_t current_page; +} error_screen_s; + + +/** + * @brief Current display state. + * + */ +typedef struct +{ + screen_t current_screen; + status_screen_s status_screen; + error_screen_s error_screen; +} kia_soul_gateway_display_state_s; + + +// **************************************************************************** +// Function: update_display +// +// Purpose: Updates the display with new information. +// +// Returns: void +// +// Parameters: void +// +// **************************************************************************** +void update_display( void ); + + +#endif /* _OSCC_KIA_SOUL_CAN_GATEWAY_DISPLAY_H_ */ diff --git a/platforms/kia_soul/firmware/can_gateway/include/globals.h b/platforms/kia_soul/firmware/can_gateway/include/globals.h index eb51f86a..56ad3e22 100644 --- a/platforms/kia_soul/firmware/can_gateway/include/globals.h +++ b/platforms/kia_soul/firmware/can_gateway/include/globals.h @@ -12,6 +12,9 @@ #include "mcp_can.h" #include "gateway_can_protocol.h" #include "chassis_state_can_protocol.h" +#include "ssd1325.h" + +#include "display.h" /* @@ -26,15 +29,59 @@ */ #define PIN_CONTROL_CAN_CHIP_SELECT ( 10 ) +/* + * @brief SPI SCLK pin to display. + * + */ +#define PIN_DISPLAY_SCLK ( 13 ) + +/* + * @brief SPI MOSI pin to display. + * + */ +#define PIN_DISPLAY_MOSI ( 11 ) + +/* + * @brief SPI CS pin to display. + * + */ +#define PIN_DISPLAY_CS ( 7 ) + +/* + * @brief Reset pin to display. + * + */ +#define PIN_DISPLAY_RESET ( 6 ) + +/* + * @brief DC pin to display. + * + */ +#define PIN_DISPLAY_DC ( 5 ) + +/* + * @brief Pin of display status screen button. + * + */ +#define PIN_DISPLAY_BUTTON_STATUS ( 4 ) + +/* + * @brief Pin of display error screen button. + * + */ +#define PIN_DISPLAY_BUTTON_ERROR ( 3 ) + #ifdef GLOBAL_DEFINED MCP_CAN g_obd_can( PIN_OBD_CAN_CHIP_SELECT ); MCP_CAN g_control_can( PIN_CONTROL_CAN_CHIP_SELECT ); + SSD1325 g_display( PIN_DISPLAY_MOSI, PIN_DISPLAY_SCLK, PIN_DISPLAY_DC, PIN_DISPLAY_RESET, PIN_DISPLAY_CS ); #define EXTERN #else extern MCP_CAN g_obd_can; extern MCP_CAN g_control_can; + extern SSD1325 g_display; #define EXTERN extern #endif @@ -43,6 +90,7 @@ EXTERN oscc_report_heartbeat_s g_tx_heartbeat; EXTERN oscc_report_chassis_state_1_s g_tx_chassis_state_1; EXTERN oscc_report_chassis_state_2_s g_tx_chassis_state_2; +EXTERN kia_soul_gateway_display_state_s g_display_state; EXTERN uint32_t g_obd_steering_wheel_angle_rx_timestamp; EXTERN uint32_t g_obd_wheel_speed_rx_timestamp; diff --git a/platforms/kia_soul/firmware/can_gateway/src/communications.cpp b/platforms/kia_soul/firmware/can_gateway/src/communications.cpp index 5c8bd5ce..73b9750a 100644 --- a/platforms/kia_soul/firmware/can_gateway/src/communications.cpp +++ b/platforms/kia_soul/firmware/can_gateway/src/communications.cpp @@ -6,6 +6,9 @@ #include "gateway_can_protocol.h" #include "chassis_state_can_protocol.h" +#include "brake_can_protocol.h" +#include "steering_can_protocol.h" +#include "throttle_can_protocol.h" #include "mcp_can.h" #include "oscc_can.h" #include "oscc_time.h" @@ -13,6 +16,7 @@ #include "globals.h" #include "communications.h" #include "obd_can_protocol.h" +#include "display.h" static void publish_heartbeat_report( void ); @@ -33,6 +37,15 @@ static void process_obd_brake_pressure( static void process_obd_turn_signal( const uint8_t * const data ); +static void process_brake_report( + const uint8_t * const data ); + +static void process_steering_report( + const uint8_t * const data ); + +static void process_throttle_report( + const uint8_t * const data ); + static void process_rx_frame( const can_frame_s * const rx_frame ); @@ -259,6 +272,68 @@ static void process_obd_turn_signal( } +static void process_brake_report( + const uint8_t * const data ) +{ + if ( data != NULL ) + { + oscc_report_brake_data_s * brake_report_data = + (oscc_report_brake_data_s *) data; + + if ( brake_report_data->enabled == true ) + { + g_display_state.status_screen.brake_status = MODULE_STATUS_ENABLED; + } + else + { + g_display_state.status_screen.brake_status = MODULE_STATUS_DISABLED; + } + } +} + + +static void process_steering_report( + const uint8_t * const data ) +{ + if ( data != NULL ) + { + oscc_report_steering_data_s * steering_report_data = + (oscc_report_steering_data_s *) data; + + if ( steering_report_data->enabled == true ) + { + g_display_state.status_screen.steering_status = MODULE_STATUS_ENABLED; + } + else + { + g_display_state.status_screen.steering_status = MODULE_STATUS_DISABLED; + } + } +} + + + +static void process_throttle_report( + const uint8_t * const data ) +{ + if ( data != NULL ) + { + oscc_report_throttle_data_s * throttle_report_data = + (oscc_report_throttle_data_s *) data; + + if ( throttle_report_data->enabled == true ) + { + g_display_state.status_screen.throttle_status = MODULE_STATUS_ENABLED; + } + else + { + g_display_state.status_screen.throttle_status = MODULE_STATUS_DISABLED; + } + } +} + + + static void process_rx_frame( const can_frame_s * const rx_frame ) { @@ -280,5 +355,17 @@ static void process_rx_frame( { process_obd_turn_signal( rx_frame->data ); } + else if( rx_frame->id == OSCC_REPORT_BRAKE_CAN_ID ) + { + process_brake_report( rx_frame->data ); + } + else if( rx_frame->id == OSCC_REPORT_STEERING_CAN_ID ) + { + process_steering_report( rx_frame->data ); + } + else if( rx_frame->id == OSCC_REPORT_THROTTLE_CAN_ID ) + { + process_throttle_report( rx_frame->data ); + } } } diff --git a/platforms/kia_soul/firmware/can_gateway/src/display.cpp b/platforms/kia_soul/firmware/can_gateway/src/display.cpp new file mode 100644 index 00000000..6dfd25c8 --- /dev/null +++ b/platforms/kia_soul/firmware/can_gateway/src/display.cpp @@ -0,0 +1,159 @@ +/** + * @file display.cpp + * + */ + +#include "globals.h" +#include "debug.h" + +#include "display.h" + + +static const char * gateway_status_strings[] = { + "UNKNOWN", + "GOOD", + "WARNING", + "ERROR" +}; + +static const char * module_status_strings[] = { + "UNKNOWN", + "ENABLED", + "DISABLED", + "ERROR" +}; + + +static void read_buttons( void ); +static void display_status_screen( void ); +static void display_error_screen( void ); +static void print_gateway_status( gateway_status_t status ); +static void print_module_status( module_status_t status ); + + +void update_display( void ) +{ + g_display.setCursor( 0, 0 ); + g_display.setTextColor( WHITE, BLACK ); + + read_buttons( ); + + if( g_display_state.current_screen == STATUS_SCREEN ) + { + display_status_screen( ); + } + else if( g_display_state.current_screen == ERROR_SCREEN ) + { + display_error_screen( ); + } +} + + +static void read_buttons( void ) +{ + int status_button = digitalRead( PIN_DISPLAY_BUTTON_STATUS ); + int error_button = digitalRead( PIN_DISPLAY_BUTTON_ERROR ); + + if( g_display_state.current_screen == STATUS_SCREEN ) + { + if( status_button == 1 ) + { + g_display_state.status_screen.current_page = + (status_page_t) ( (g_display_state.status_screen.current_page + 1) + % STATUS_PAGE_COUNT ); + } + else if( error_button == 1 ) + { + g_display_state.current_screen = ERROR_SCREEN; + g_display_state.error_screen.current_page = ERROR_PAGE_MAIN; + } + } + else if( g_display_state.current_screen == ERROR_SCREEN ) + { + if( status_button == 1 ) + { + g_display_state.current_screen = STATUS_SCREEN; + g_display_state.status_screen.current_page = STATUS_PAGE_MAIN; + } + else if( error_button == 1 ) + { + g_display_state.error_screen.current_page = + (error_page_t) ( (g_display_state.error_screen.current_page + 1) + % ERROR_PAGE_COUNT ); + } + } +} + + +static void display_status_screen( void ) +{ + g_display.eraseBuffer(); + + if( g_display_state.status_screen.current_page == STATUS_PAGE_MAIN) + { + g_display.print( "Gateway: " ); + print_gateway_status( g_display_state.status_screen.gateway_status ); + + g_display.print( "Brakes: " ); + print_module_status( g_display_state.status_screen.brake_status.status ); + + g_display.print( "Steering: " ); + print_module_status( g_display_state.status_screen.steering_status ); + + g_display.print( "Throttle: " ); + print_module_status( g_display_state.status_screen.throttle_status ); + } + + g_display.sendBuffer(); +} + + +static void display_error_screen( void ) +{ + g_display.eraseBuffer( ); + + if( g_display_state.error_screen.current_page == ERROR_PAGE_MAIN) + { + g_display.print( "Errors\n" ); + } + + g_display.sendBuffer( ); +} + + +static void print_gateway_status( gateway_status_t status ) +{ + const char * status_string = gateway_status_strings[status]; + + if( status == GATEWAY_STATUS_ERROR ) + { + g_display.setTextColor( BLACK, WHITE ); + g_display.print( status_string ); + g_display.setTextColor( WHITE, BLACK ); + } + else + { + g_display.print( status_string ); + } + + g_display.print( "\n\n") ; +} + + +static void print_module_status( module_status_t status ) +{ + const char * status_string = module_status_strings[status]; + + if( status == MODULE_STATUS_ERROR ) + { + g_display.setTextColor( BLACK, WHITE ); + g_display.print( status_string ); + g_display.setTextColor( WHITE, BLACK ); + } + else + { + g_display.print( status_string ); + } + + g_display.print( "\n\n" ); +} diff --git a/platforms/kia_soul/firmware/can_gateway/src/init.cpp b/platforms/kia_soul/firmware/can_gateway/src/init.cpp index 0826a766..b2a9cb93 100644 --- a/platforms/kia_soul/firmware/can_gateway/src/init.cpp +++ b/platforms/kia_soul/firmware/can_gateway/src/init.cpp @@ -31,6 +31,11 @@ void init_globals( void ) 0, sizeof(g_tx_chassis_state_2) ); + memset( + &g_display_state, + 0, + sizeof(g_display_state) ); + // initialize timestamps so that we don't get timeouts on start g_obd_steering_wheel_angle_rx_timestamp = GET_TIMESTAMP_MS(); g_obd_wheel_speed_rx_timestamp = GET_TIMESTAMP_MS(); @@ -56,4 +61,7 @@ void init_communication_interfaces( void ) DEBUG_PRINT( "init Control CAN - "); init_can( g_control_can ); + + DEBUG_PRINT( "init display"); + g_display.begin(); } diff --git a/platforms/kia_soul/firmware/can_gateway/src/main.cpp b/platforms/kia_soul/firmware/can_gateway/src/main.cpp index f2d5a8f2..f63dd557 100644 --- a/platforms/kia_soul/firmware/can_gateway/src/main.cpp +++ b/platforms/kia_soul/firmware/can_gateway/src/main.cpp @@ -13,6 +13,7 @@ #include "globals.h" #include "communications.h" #include "init.h" +#include "display.h" int main( void ) @@ -25,7 +26,7 @@ int main( void ) SET_HEARTBEAT_STATE( OSCC_REPORT_HEARTBEAT_STATE_OK ); - wdt_enable( WDTO_120MS ); + wdt_enable( WDTO_250MS ); DEBUG_PRINTLN( "initialization complete" ); @@ -35,6 +36,8 @@ int main( void ) check_for_incoming_message( ); + update_display( ); + check_for_obd_timeout( ); publish_reports( ); From 8d2459f5b1b0c4f2150e413d6aa4e7bd5dc2a03c Mon Sep 17 00:00:00 2001 From: Austin Morlan Date: Wed, 28 Jun 2017 11:33:30 -0700 Subject: [PATCH 03/84] Add msg receive counters to status pages --- .../firmware/can_gateway/include/display.h | 59 +++++++++++++++++-- .../can_gateway/src/communications.cpp | 26 ++++++-- .../firmware/can_gateway/src/display.cpp | 47 +++++++++++++-- 3 files changed, 116 insertions(+), 16 deletions(-) diff --git a/platforms/kia_soul/firmware/can_gateway/include/display.h b/platforms/kia_soul/firmware/can_gateway/include/display.h index 9b46820f..4db7c5ef 100644 --- a/platforms/kia_soul/firmware/can_gateway/include/display.h +++ b/platforms/kia_soul/firmware/can_gateway/include/display.h @@ -28,6 +28,10 @@ typedef enum typedef enum { STATUS_PAGE_MAIN, + STATUS_PAGE_GATEWAY, + STATUS_PAGE_BRAKES, + STATUS_PAGE_STEERING, + STATUS_PAGE_THROTTLE, STATUS_PAGE_COUNT } status_page_t; @@ -69,6 +73,53 @@ typedef enum } module_status_t; +/** + * @brief Gateway status page data. + * + */ +typedef struct +{ + gateway_status_t status; + unsigned long obd_steering_wheel_angle_msg_rcvd_count; + unsigned long obd_wheel_speed_msg_rcvd_count; + unsigned long obd_brake_pressure_msg_rcvd_count; + unsigned long obd_turn_signal_msg_rcvd_count; +} status_page_gateway_s; + + +/** + * @brief Brake status page data. + * + */ +typedef struct +{ + module_status_t status; + unsigned long msg_rcvd_count; +} status_page_brake_s; + + +/** + * @brief Steering status page data. + * + */ +typedef struct +{ + module_status_t status; + unsigned long msg_rcvd_count; +} status_page_steering_s; + + +/** + * @brief Throttle status page data. + * + */ +typedef struct +{ + module_status_t status; + unsigned long msg_rcvd_count; +} status_page_throttle_s; + + /** * @brief Current status screen state. * @@ -76,10 +127,10 @@ typedef enum typedef struct { status_page_t current_page; - gateway_status_t gateway_status; - module_status_t brake_status; - module_status_t steering_status; - module_status_t throttle_status; + status_page_gateway_s gateway; + status_page_brake_s brakes; + status_page_steering_s steering; + status_page_throttle_s throttle; } status_screen_s; diff --git a/platforms/kia_soul/firmware/can_gateway/src/communications.cpp b/platforms/kia_soul/firmware/can_gateway/src/communications.cpp index 73b9750a..86867cc7 100644 --- a/platforms/kia_soul/firmware/can_gateway/src/communications.cpp +++ b/platforms/kia_soul/firmware/can_gateway/src/communications.cpp @@ -202,6 +202,8 @@ static void process_obd_steering_wheel_angle( g_tx_chassis_state_1.data.steering_wheel_angle = steering_wheel_angle_data->steering_angle; g_obd_steering_wheel_angle_rx_timestamp = GET_TIMESTAMP_MS( ); + + ++g_display_state.status_screen.gateway.obd_steering_wheel_angle_msg_rcvd_count; } } @@ -223,6 +225,8 @@ static void process_obd_wheel_speed( g_tx_chassis_state_2.data.wheel_speed_rear_right = wheel_speed_data->wheel_speed_rear_right; g_obd_wheel_speed_rx_timestamp = GET_TIMESTAMP_MS( ); + + ++g_display_state.status_screen.gateway.obd_wheel_speed_msg_rcvd_count; } } @@ -241,6 +245,8 @@ static void process_obd_brake_pressure( g_tx_chassis_state_1.data.brake_pressure = brake_pressure_data->master_cylinder_pressure; g_obd_brake_pressure_rx_timestamp = GET_TIMESTAMP_MS( ); + + ++g_display_state.status_screen.gateway.obd_brake_pressure_msg_rcvd_count; } } @@ -268,6 +274,8 @@ static void process_obd_turn_signal( } g_obd_turn_signal_rx_timestamp = GET_TIMESTAMP_MS( ); + + ++g_display_state.status_screen.gateway.obd_turn_signal_msg_rcvd_count; } } @@ -282,12 +290,14 @@ static void process_brake_report( if ( brake_report_data->enabled == true ) { - g_display_state.status_screen.brake_status = MODULE_STATUS_ENABLED; + g_display_state.status_screen.brakes.status = MODULE_STATUS_ENABLED; } else { - g_display_state.status_screen.brake_status = MODULE_STATUS_DISABLED; + g_display_state.status_screen.brakes.status = MODULE_STATUS_DISABLED; } + + ++g_display_state.status_screen.brakes.msg_rcvd_count; } } @@ -302,12 +312,14 @@ static void process_steering_report( if ( steering_report_data->enabled == true ) { - g_display_state.status_screen.steering_status = MODULE_STATUS_ENABLED; + g_display_state.status_screen.steering.status = MODULE_STATUS_ENABLED; } else { - g_display_state.status_screen.steering_status = MODULE_STATUS_DISABLED; + g_display_state.status_screen.steering.status = MODULE_STATUS_DISABLED; } + + ++g_display_state.status_screen.steering.msg_rcvd_count; } } @@ -323,12 +335,14 @@ static void process_throttle_report( if ( throttle_report_data->enabled == true ) { - g_display_state.status_screen.throttle_status = MODULE_STATUS_ENABLED; + g_display_state.status_screen.throttle.status = MODULE_STATUS_ENABLED; } else { - g_display_state.status_screen.throttle_status = MODULE_STATUS_DISABLED; + g_display_state.status_screen.throttle.status = MODULE_STATUS_DISABLED; } + + ++g_display_state.status_screen.throttle.msg_rcvd_count; } } diff --git a/platforms/kia_soul/firmware/can_gateway/src/display.cpp b/platforms/kia_soul/firmware/can_gateway/src/display.cpp index 6dfd25c8..cb187c6f 100644 --- a/platforms/kia_soul/firmware/can_gateway/src/display.cpp +++ b/platforms/kia_soul/firmware/can_gateway/src/display.cpp @@ -9,14 +9,16 @@ #include "display.h" -static const char * gateway_status_strings[] = { +static const char * gateway_status_strings[] = +{ "UNKNOWN", "GOOD", "WARNING", "ERROR" }; -static const char * module_status_strings[] = { +static const char * module_status_strings[] = +{ "UNKNOWN", "ENABLED", "DISABLED", @@ -92,16 +94,49 @@ static void display_status_screen( void ) if( g_display_state.status_screen.current_page == STATUS_PAGE_MAIN) { g_display.print( "Gateway: " ); - print_gateway_status( g_display_state.status_screen.gateway_status ); + print_gateway_status( g_display_state.status_screen.gateway.status ); g_display.print( "Brakes: " ); - print_module_status( g_display_state.status_screen.brake_status.status ); + print_module_status( g_display_state.status_screen.brakes.status ); g_display.print( "Steering: " ); - print_module_status( g_display_state.status_screen.steering_status ); + print_module_status( g_display_state.status_screen.steering.status ); g_display.print( "Throttle: " ); - print_module_status( g_display_state.status_screen.throttle_status ); + print_module_status( g_display_state.status_screen.throttle.status ); + } + else if( g_display_state.status_screen.current_page == STATUS_PAGE_GATEWAY ) + { + g_display.print( "Gateway\n\n" ); + g_display.print( "OBD1 Rcvd: " ); + g_display.println( g_display_state.status_screen.gateway.obd_steering_wheel_angle_msg_rcvd_count ); + + g_display.print( "OBD2 Rcvd: " ); + g_display.println( g_display_state.status_screen.gateway.obd_wheel_speed_msg_rcvd_count ); + + g_display.print( "OBD3 Rcvd: " ); + g_display.println( g_display_state.status_screen.gateway.obd_brake_pressure_msg_rcvd_count ); + + g_display.print( "OBD4 Rcvd: " ); + g_display.println( g_display_state.status_screen.gateway.obd_turn_signal_msg_rcvd_count ); + } + else if( g_display_state.status_screen.current_page == STATUS_PAGE_BRAKES ) + { + g_display.print( "Brakes\n\n" ); + g_display.print( "Msgs Rcvd: " ); + g_display.print( g_display_state.status_screen.brakes.msg_rcvd_count ); + } + else if( g_display_state.status_screen.current_page == STATUS_PAGE_STEERING ) + { + g_display.print( "Steering\n\n" ); + g_display.print( "Msgs Rcvd: " ); + g_display.print( g_display_state.status_screen.steering.msg_rcvd_count ); + } + else if( g_display_state.status_screen.current_page == STATUS_PAGE_THROTTLE ) + { + g_display.print( "Throttle\n\n" ); + g_display.print( "Msgs Rcvd: " ); + g_display.print( g_display_state.status_screen.throttle.msg_rcvd_count ); } g_display.sendBuffer(); From c44edd9d73e10ef42e6ada1500783fa966c79375 Mon Sep 17 00:00:00 2001 From: Austin Morlan Date: Fri, 30 Jun 2017 11:36:34 -0700 Subject: [PATCH 04/84] Rename faults to DTCs --- platforms/common/include/brake_can_protocol.h | 14 +++++++------- platforms/common/include/steering_can_protocol.h | 8 ++++---- platforms/common/include/throttle_can_protocol.h | 2 +- .../kia_soul/firmware/brake/src/communications.cpp | 8 ++++---- .../firmware/steering/src/communications.cpp | 4 ++-- .../firmware/throttle/src/communications.cpp | 2 +- utils/diagnostics_tool/src/brake_module_state.c | 2 +- utils/diagnostics_tool/src/steering_module_state.c | 2 +- utils/joystick_commander/src/oscc_interface.c | 14 +++++++------- 9 files changed, 28 insertions(+), 28 deletions(-) diff --git a/platforms/common/include/brake_can_protocol.h b/platforms/common/include/brake_can_protocol.h index df909288..4e335a71 100644 --- a/platforms/common/include/brake_can_protocol.h +++ b/platforms/common/include/brake_can_protocol.h @@ -121,24 +121,24 @@ typedef struct * Value zero means controls are provided autonomously (no override). * Value one means controls are provided by the driver. */ - uint8_t fault_invalid_sensor_value : 1; /*!< Invalid sensor value indicator. + uint8_t dtc00_invalid_sensor_value : 1; /*!< Invalid sensor value indicator. * Value zero means the values read * from the sensors are valid. * * Value one means the values read * from the sensors are invalid. */ - uint8_t fault_startup_pressure_check_error : 1; /*!< Actuator sensors report + uint8_t dtc01_obd_timeout : 1; /*!< OBD timeout indicator. + * Value zero means no timeout occurred. + * Value one means timeout occurred. */ + + uint8_t dtc02_startup_pressure_check_error : 1; /*!< Actuator sensors report * values that do not match * the static values * expected with PCK1 and * PCK2 asserted. */ - uint8_t fault_obd_timeout : 1; /*!< OBD timeout indicator. - * Value zero means no timeout occurred. - * Value one means timeout occurred. */ - - uint8_t fault_startup_pump_motor_check_error : 1; /*!< Pump motor check signal + uint8_t dtc03_startup_pump_motor_check_error : 1; /*!< Pump motor check signal * (MTT) is not asserted * when pump is on. */ diff --git a/platforms/common/include/steering_can_protocol.h b/platforms/common/include/steering_can_protocol.h index a6663cdd..2fb22c6e 100644 --- a/platforms/common/include/steering_can_protocol.h +++ b/platforms/common/include/steering_can_protocol.h @@ -124,19 +124,19 @@ typedef struct * Value zero means controls are provided autonomously (no override). * Value one means controls are provided by the driver. */ - uint8_t fault_invalid_sensor_value : 1; /*!< Invalid sensor value indicator. + uint8_t dtc00_invalid_sensor_value : 1; /*!< Invalid sensor value indicator. * Value zero means the values read * from the sensors are valid. * * Value one means the values read * from the sensors are invalid. */ - uint8_t reserved_1 : 1; /*!< Reserved. */ - - uint8_t fault_obd_timeout : 1; /*!< OBD timeout indicator. + uint8_t dtc01_obd_timeout : 1; /*!< OBD timeout indicator. * Value zero means no timeout occurred. * Value one means timeout occurred. */ + uint8_t reserved_1 : 1; /*!< Reserved. */ + uint8_t reserved_2 : 1; /*!< Reserved */ uint8_t reserved_3 : 1; /*!< Reserved. */ diff --git a/platforms/common/include/throttle_can_protocol.h b/platforms/common/include/throttle_can_protocol.h index c7c068aa..8643cca7 100644 --- a/platforms/common/include/throttle_can_protocol.h +++ b/platforms/common/include/throttle_can_protocol.h @@ -119,7 +119,7 @@ typedef struct * Value zero means controls are provided autonomously (no override). * Value one means controls are provided by the driver. */ - uint8_t fault_invalid_sensor_value : 1; /*!< Invalid sensor value indicator. + uint8_t dtc00_invalid_sensor_value : 1; /*!< Invalid sensor value indicator. * Value zero means the values read * from the sensors are valid. * diff --git a/platforms/kia_soul/firmware/brake/src/communications.cpp b/platforms/kia_soul/firmware/brake/src/communications.cpp index 13f4fe57..2131fff2 100644 --- a/platforms/kia_soul/firmware/brake/src/communications.cpp +++ b/platforms/kia_soul/firmware/brake/src/communications.cpp @@ -74,10 +74,10 @@ static void publish_brake_report( void ) brake_report.data.pedal_input = (int16_t) g_brake_control_state.current_vehicle_brake_pressure; brake_report.data.pedal_command = (uint16_t) g_brake_control_state.commanded_pedal_position; brake_report.data.pedal_output = (uint16_t) g_brake_control_state.current_sensor_brake_pressure; - brake_report.data.fault_obd_timeout = (uint8_t) g_brake_control_state.obd_timeout; - brake_report.data.fault_invalid_sensor_value = (uint8_t) g_brake_control_state.invalid_sensor_value; - brake_report.data.fault_startup_pressure_check_error = (uint8_t) g_brake_control_state.startup_pressure_check_error; - brake_report.data.fault_startup_pump_motor_check_error = (uint8_t) g_brake_control_state.startup_pump_motor_check_error; + brake_report.data.dtc00_invalid_sensor_value = (uint8_t) g_brake_control_state.invalid_sensor_value; + brake_report.data.dtc01_obd_timeout = (uint8_t) g_brake_control_state.obd_timeout; + brake_report.data.dtc02_startup_pressure_check_error = (uint8_t) g_brake_control_state.startup_pressure_check_error; + brake_report.data.dtc03_startup_pump_motor_check_error = (uint8_t) g_brake_control_state.startup_pump_motor_check_error; g_control_can.sendMsgBuf( brake_report.id, diff --git a/platforms/kia_soul/firmware/steering/src/communications.cpp b/platforms/kia_soul/firmware/steering/src/communications.cpp index 9f7e1a7f..827711d3 100644 --- a/platforms/kia_soul/firmware/steering/src/communications.cpp +++ b/platforms/kia_soul/firmware/steering/src/communications.cpp @@ -73,9 +73,9 @@ static void publish_steering_report( void ) steering_report.data.override = (uint8_t) g_steering_control_state.operator_override; steering_report.data.current_steering_wheel_angle = (int16_t) g_steering_control_state.current_steering_wheel_angle; steering_report.data.commanded_steering_wheel_angle = (int16_t) g_steering_control_state.commanded_steering_wheel_angle; - steering_report.data.fault_obd_timeout = (uint8_t) g_steering_control_state.obd_timeout; steering_report.data.spoofed_torque_output = (int8_t) g_spoofed_torque_output_sum; - steering_report.data.fault_invalid_sensor_value = (uint8_t) g_steering_control_state.invalid_sensor_value; + steering_report.data.dtc00_invalid_sensor_value = (uint8_t) g_steering_control_state.invalid_sensor_value; + steering_report.data.dtc01_obd_timeout = (uint8_t) g_steering_control_state.obd_timeout; g_control_can.sendMsgBuf( steering_report.id, diff --git a/platforms/kia_soul/firmware/throttle/src/communications.cpp b/platforms/kia_soul/firmware/throttle/src/communications.cpp index a929e163..95ccfbd9 100644 --- a/platforms/kia_soul/firmware/throttle/src/communications.cpp +++ b/platforms/kia_soul/firmware/throttle/src/communications.cpp @@ -82,7 +82,7 @@ static void publish_throttle_report( void ) throttle_report.data.commanded_accelerator_position = g_throttle_control_state.commanded_accelerator_position; throttle_report.data.spoofed_accelerator_output = g_accelerator_spoof_output_sum; - throttle_report.data.fault_invalid_sensor_value = + throttle_report.data.dtc00_invalid_sensor_value = g_throttle_control_state.invalid_sensor_value; g_control_can.sendMsgBuf( diff --git a/utils/diagnostics_tool/src/brake_module_state.c b/utils/diagnostics_tool/src/brake_module_state.c index 6b168dab..52197feb 100644 --- a/utils/diagnostics_tool/src/brake_module_state.c +++ b/utils/diagnostics_tool/src/brake_module_state.c @@ -47,7 +47,7 @@ static int analyze_report_frame( state->override_triggered = brake_report->override; - if( brake_report->fault_obd_timeout == 1 ) + if( brake_report->dtc01_obd_timeout == 1 ) { module_state = STATE_FAULT; } diff --git a/utils/diagnostics_tool/src/steering_module_state.c b/utils/diagnostics_tool/src/steering_module_state.c index b49ab47b..24e24e67 100644 --- a/utils/diagnostics_tool/src/steering_module_state.c +++ b/utils/diagnostics_tool/src/steering_module_state.c @@ -54,7 +54,7 @@ static int analyze_report_frame( state->override_triggered = steering_report->override; - if( steering_report->fault_obd_timeout == 1 ) + if( steering_report->dtc01_obd_timeout == 1 ) { module_state = STATE_FAULT; } diff --git a/utils/joystick_commander/src/oscc_interface.c b/utils/joystick_commander/src/oscc_interface.c index dbedbbef..f7e05ae6 100644 --- a/utils/joystick_commander/src/oscc_interface.c +++ b/utils/joystick_commander/src/oscc_interface.c @@ -175,10 +175,10 @@ static void oscc_interface_check_brake_faults( ( oscc_report_brake_data_s* )buffer; status->operator_override = (bool) brake_report_data->override; - status->fault_brake_obd_timeout = (bool) brake_report_data->fault_obd_timeout; - status->fault_brake_invalid_sensor_value = (bool) brake_report_data->fault_invalid_sensor_value; - status->fault_brake_actuator_error = (bool) brake_report_data->fault_startup_pressure_check_error; - status->fault_brake_pump_motor_error = (bool) brake_report_data->fault_startup_pump_motor_check_error; + status->fault_brake_invalid_sensor_value = (bool) brake_report_data->dtc00_invalid_sensor_value; + status->fault_brake_obd_timeout = (bool) brake_report_data->dtc01_obd_timeout; + status->fault_brake_actuator_error = (bool) brake_report_data->dtc02_startup_pressure_check_error; + status->fault_brake_pump_motor_error = (bool) brake_report_data->dtc03_startup_pump_motor_check_error; } } @@ -206,8 +206,8 @@ static bool oscc_interface_check_steering_faults( ( oscc_report_steering_data_s* )buffer; status->operator_override = (bool) steering_report_data->override; - status->fault_steering_obd_timeout = (bool) steering_report_data->fault_obd_timeout; - status->fault_steering_invalid_sensor_value = (bool) steering_report_data->fault_invalid_sensor_value; + status->fault_steering_invalid_sensor_value = (bool) steering_report_data->dtc00_invalid_sensor_value; + status->fault_steering_obd_timeout = (bool) steering_report_data->dtc01_obd_timeout; } } @@ -235,7 +235,7 @@ static bool oscc_interface_check_throttle_faults( ( oscc_report_throttle_data_s* )buffer; status->operator_override = (bool) throttle_report_data->override; - status->fault_throttle_invalid_sensor_value = (bool) throttle_report_data->fault_invalid_sensor_value; + status->fault_throttle_invalid_sensor_value = (bool) throttle_report_data->dtc00_invalid_sensor_value; } } From 2930caf18c87e3ca0cd30b8919801390d0ad44b7 Mon Sep 17 00:00:00 2001 From: Austin Morlan Date: Fri, 30 Jun 2017 11:52:46 -0700 Subject: [PATCH 05/84] Change from multiple status and error pages to two --- .../firmware/can_gateway/include/display.h | 84 +--------------- .../can_gateway/src/communications.cpp | 26 ++--- .../firmware/can_gateway/src/display.cpp | 95 ++++--------------- 3 files changed, 27 insertions(+), 178 deletions(-) diff --git a/platforms/kia_soul/firmware/can_gateway/include/display.h b/platforms/kia_soul/firmware/can_gateway/include/display.h index 4db7c5ef..cfa3aafc 100644 --- a/platforms/kia_soul/firmware/can_gateway/include/display.h +++ b/platforms/kia_soul/firmware/can_gateway/include/display.h @@ -21,32 +21,6 @@ typedef enum } screen_t; -/** - * @brief Enumeration of possible status pages. - * - */ -typedef enum -{ - STATUS_PAGE_MAIN, - STATUS_PAGE_GATEWAY, - STATUS_PAGE_BRAKES, - STATUS_PAGE_STEERING, - STATUS_PAGE_THROTTLE, - STATUS_PAGE_COUNT -} status_page_t; - - -/** - * @brief Enumeration of possible error pages. - * - */ -typedef enum -{ - ERROR_PAGE_MAIN, - ERROR_PAGE_COUNT -} error_page_t; - - /** * @brief Enumeration of possible gateway statuses. * @@ -73,64 +47,16 @@ typedef enum } module_status_t; -/** - * @brief Gateway status page data. - * - */ -typedef struct -{ - gateway_status_t status; - unsigned long obd_steering_wheel_angle_msg_rcvd_count; - unsigned long obd_wheel_speed_msg_rcvd_count; - unsigned long obd_brake_pressure_msg_rcvd_count; - unsigned long obd_turn_signal_msg_rcvd_count; -} status_page_gateway_s; - - -/** - * @brief Brake status page data. - * - */ -typedef struct -{ - module_status_t status; - unsigned long msg_rcvd_count; -} status_page_brake_s; - - -/** - * @brief Steering status page data. - * - */ -typedef struct -{ - module_status_t status; - unsigned long msg_rcvd_count; -} status_page_steering_s; - - -/** - * @brief Throttle status page data. - * - */ -typedef struct -{ - module_status_t status; - unsigned long msg_rcvd_count; -} status_page_throttle_s; - - /** * @brief Current status screen state. * */ typedef struct { - status_page_t current_page; - status_page_gateway_s gateway; - status_page_brake_s brakes; - status_page_steering_s steering; - status_page_throttle_s throttle; + gateway_status_t gateway; + module_status_t brakes; + module_status_t steering; + module_status_t throttle; } status_screen_s; @@ -140,7 +66,7 @@ typedef struct */ typedef struct { - error_page_t current_page; + } error_screen_s; diff --git a/platforms/kia_soul/firmware/can_gateway/src/communications.cpp b/platforms/kia_soul/firmware/can_gateway/src/communications.cpp index 86867cc7..19fa3f90 100644 --- a/platforms/kia_soul/firmware/can_gateway/src/communications.cpp +++ b/platforms/kia_soul/firmware/can_gateway/src/communications.cpp @@ -202,8 +202,6 @@ static void process_obd_steering_wheel_angle( g_tx_chassis_state_1.data.steering_wheel_angle = steering_wheel_angle_data->steering_angle; g_obd_steering_wheel_angle_rx_timestamp = GET_TIMESTAMP_MS( ); - - ++g_display_state.status_screen.gateway.obd_steering_wheel_angle_msg_rcvd_count; } } @@ -225,8 +223,6 @@ static void process_obd_wheel_speed( g_tx_chassis_state_2.data.wheel_speed_rear_right = wheel_speed_data->wheel_speed_rear_right; g_obd_wheel_speed_rx_timestamp = GET_TIMESTAMP_MS( ); - - ++g_display_state.status_screen.gateway.obd_wheel_speed_msg_rcvd_count; } } @@ -245,8 +241,6 @@ static void process_obd_brake_pressure( g_tx_chassis_state_1.data.brake_pressure = brake_pressure_data->master_cylinder_pressure; g_obd_brake_pressure_rx_timestamp = GET_TIMESTAMP_MS( ); - - ++g_display_state.status_screen.gateway.obd_brake_pressure_msg_rcvd_count; } } @@ -274,8 +268,6 @@ static void process_obd_turn_signal( } g_obd_turn_signal_rx_timestamp = GET_TIMESTAMP_MS( ); - - ++g_display_state.status_screen.gateway.obd_turn_signal_msg_rcvd_count; } } @@ -290,14 +282,12 @@ static void process_brake_report( if ( brake_report_data->enabled == true ) { - g_display_state.status_screen.brakes.status = MODULE_STATUS_ENABLED; + g_display_state.status_screen.brakes = MODULE_STATUS_ENABLED; } else { - g_display_state.status_screen.brakes.status = MODULE_STATUS_DISABLED; + g_display_state.status_screen.brakes = MODULE_STATUS_DISABLED; } - - ++g_display_state.status_screen.brakes.msg_rcvd_count; } } @@ -312,14 +302,12 @@ static void process_steering_report( if ( steering_report_data->enabled == true ) { - g_display_state.status_screen.steering.status = MODULE_STATUS_ENABLED; + g_display_state.status_screen.steering = MODULE_STATUS_ENABLED; } else { - g_display_state.status_screen.steering.status = MODULE_STATUS_DISABLED; + g_display_state.status_screen.steering = MODULE_STATUS_DISABLED; } - - ++g_display_state.status_screen.steering.msg_rcvd_count; } } @@ -335,14 +323,12 @@ static void process_throttle_report( if ( throttle_report_data->enabled == true ) { - g_display_state.status_screen.throttle.status = MODULE_STATUS_ENABLED; + g_display_state.status_screen.throttle = MODULE_STATUS_ENABLED; } else { - g_display_state.status_screen.throttle.status = MODULE_STATUS_DISABLED; + g_display_state.status_screen.throttle = MODULE_STATUS_DISABLED; } - - ++g_display_state.status_screen.throttle.msg_rcvd_count; } } diff --git a/platforms/kia_soul/firmware/can_gateway/src/display.cpp b/platforms/kia_soul/firmware/can_gateway/src/display.cpp index cb187c6f..70f742ea 100644 --- a/platforms/kia_soul/firmware/can_gateway/src/display.cpp +++ b/platforms/kia_soul/firmware/can_gateway/src/display.cpp @@ -26,7 +26,7 @@ static const char * module_status_strings[] = }; -static void read_buttons( void ); +static void read_button( void ); static void display_status_screen( void ); static void display_error_screen( void ); static void print_gateway_status( gateway_status_t status ); @@ -38,7 +38,7 @@ void update_display( void ) g_display.setCursor( 0, 0 ); g_display.setTextColor( WHITE, BLACK ); - read_buttons( ); + read_button( ); if( g_display_state.current_screen == STATUS_SCREEN ) { @@ -51,38 +51,14 @@ void update_display( void ) } -static void read_buttons( void ) +static void read_button( void ) { - int status_button = digitalRead( PIN_DISPLAY_BUTTON_STATUS ); - int error_button = digitalRead( PIN_DISPLAY_BUTTON_ERROR ); + int button_val = digitalRead( PIN_DISPLAY_BUTTON_STATUS ); - if( g_display_state.current_screen == STATUS_SCREEN ) + if( button_val == 1 ) { - if( status_button == 1 ) - { - g_display_state.status_screen.current_page = - (status_page_t) ( (g_display_state.status_screen.current_page + 1) - % STATUS_PAGE_COUNT ); - } - else if( error_button == 1 ) - { - g_display_state.current_screen = ERROR_SCREEN; - g_display_state.error_screen.current_page = ERROR_PAGE_MAIN; - } - } - else if( g_display_state.current_screen == ERROR_SCREEN ) - { - if( status_button == 1 ) - { - g_display_state.current_screen = STATUS_SCREEN; - g_display_state.status_screen.current_page = STATUS_PAGE_MAIN; - } - else if( error_button == 1 ) - { - g_display_state.error_screen.current_page = - (error_page_t) ( (g_display_state.error_screen.current_page + 1) - % ERROR_PAGE_COUNT ); - } + g_display_state.current_screen = + (screen_t)((g_display_state.current_screen + 1) % SCREEN_COUNT); } } @@ -91,53 +67,17 @@ static void display_status_screen( void ) { g_display.eraseBuffer(); - if( g_display_state.status_screen.current_page == STATUS_PAGE_MAIN) - { - g_display.print( "Gateway: " ); - print_gateway_status( g_display_state.status_screen.gateway.status ); - - g_display.print( "Brakes: " ); - print_module_status( g_display_state.status_screen.brakes.status ); + g_display.print( "Gateway: " ); + print_gateway_status( g_display_state.status_screen.gateway ); - g_display.print( "Steering: " ); - print_module_status( g_display_state.status_screen.steering.status ); + g_display.print( "Brakes: " ); + print_module_status( g_display_state.status_screen.brakes ); - g_display.print( "Throttle: " ); - print_module_status( g_display_state.status_screen.throttle.status ); - } - else if( g_display_state.status_screen.current_page == STATUS_PAGE_GATEWAY ) - { - g_display.print( "Gateway\n\n" ); - g_display.print( "OBD1 Rcvd: " ); - g_display.println( g_display_state.status_screen.gateway.obd_steering_wheel_angle_msg_rcvd_count ); + g_display.print( "Steering: " ); + print_module_status( g_display_state.status_screen.steering ); - g_display.print( "OBD2 Rcvd: " ); - g_display.println( g_display_state.status_screen.gateway.obd_wheel_speed_msg_rcvd_count ); - - g_display.print( "OBD3 Rcvd: " ); - g_display.println( g_display_state.status_screen.gateway.obd_brake_pressure_msg_rcvd_count ); - - g_display.print( "OBD4 Rcvd: " ); - g_display.println( g_display_state.status_screen.gateway.obd_turn_signal_msg_rcvd_count ); - } - else if( g_display_state.status_screen.current_page == STATUS_PAGE_BRAKES ) - { - g_display.print( "Brakes\n\n" ); - g_display.print( "Msgs Rcvd: " ); - g_display.print( g_display_state.status_screen.brakes.msg_rcvd_count ); - } - else if( g_display_state.status_screen.current_page == STATUS_PAGE_STEERING ) - { - g_display.print( "Steering\n\n" ); - g_display.print( "Msgs Rcvd: " ); - g_display.print( g_display_state.status_screen.steering.msg_rcvd_count ); - } - else if( g_display_state.status_screen.current_page == STATUS_PAGE_THROTTLE ) - { - g_display.print( "Throttle\n\n" ); - g_display.print( "Msgs Rcvd: " ); - g_display.print( g_display_state.status_screen.throttle.msg_rcvd_count ); - } + g_display.print( "Throttle: " ); + print_module_status( g_display_state.status_screen.throttle ); g_display.sendBuffer(); } @@ -147,10 +87,7 @@ static void display_error_screen( void ) { g_display.eraseBuffer( ); - if( g_display_state.error_screen.current_page == ERROR_PAGE_MAIN) - { - g_display.print( "Errors\n" ); - } + g_display.print( "Errors\n" ); g_display.sendBuffer( ); } From e72f134dbc64479d1b92caf73040eb8e0720a5ba Mon Sep 17 00:00:00 2001 From: Austin Morlan Date: Fri, 30 Jun 2017 16:15:35 -0700 Subject: [PATCH 06/84] Add DTC logic --- platforms/common/include/brake_can_protocol.h | 6 + .../common/include/gateway_can_protocol.h | 6 + .../common/include/steering_can_protocol.h | 6 + .../common/include/throttle_can_protocol.h | 9 +- .../firmware/can_gateway/include/display.h | 18 +- .../can_gateway/src/communications.cpp | 69 +++++++ .../firmware/can_gateway/src/display.cpp | 173 +++++++++++++++++- 7 files changed, 272 insertions(+), 15 deletions(-) diff --git a/platforms/common/include/brake_can_protocol.h b/platforms/common/include/brake_can_protocol.h index 4e335a71..943d90a7 100644 --- a/platforms/common/include/brake_can_protocol.h +++ b/platforms/common/include/brake_can_protocol.h @@ -36,6 +36,12 @@ */ #define OSCC_REPORT_BRAKE_PUBLISH_INTERVAL_IN_MSEC (50) +/* + * @brief Number of brake module DTCs. + * + */ +#define OSCC_BRAKE_DTC_COUNT (4) + /** * @brief Brake command message data. diff --git a/platforms/common/include/gateway_can_protocol.h b/platforms/common/include/gateway_can_protocol.h index 85de393c..748e67d6 100644 --- a/platforms/common/include/gateway_can_protocol.h +++ b/platforms/common/include/gateway_can_protocol.h @@ -66,6 +66,12 @@ */ #define OSCC_REPORT_HEARTBEAT_STATE_OK (0x02) +/* + * @brief Number of gateway module DTCs. + * + */ +#define OSCC_GATEWAY_DTC_COUNT (4) + /** * @brief Heartbeat report message data. diff --git a/platforms/common/include/steering_can_protocol.h b/platforms/common/include/steering_can_protocol.h index 2fb22c6e..783c293e 100644 --- a/platforms/common/include/steering_can_protocol.h +++ b/platforms/common/include/steering_can_protocol.h @@ -36,6 +36,12 @@ */ #define OSCC_REPORT_STEERING_PUBLISH_INTERVAL_IN_MSEC (20) +/* + * @brief Number of steering module DTCs. + * + */ +#define OSCC_STEERING_DTC_COUNT (2) + /** * @brief Steering command message data. diff --git a/platforms/common/include/throttle_can_protocol.h b/platforms/common/include/throttle_can_protocol.h index 8643cca7..55b8daec 100644 --- a/platforms/common/include/throttle_can_protocol.h +++ b/platforms/common/include/throttle_can_protocol.h @@ -18,27 +18,30 @@ */ #define OSCC_COMMAND_THROTTLE_CAN_ID (0x62) - /* * @brief Throttle report message (CAN frame) ID. * */ #define OSCC_REPORT_THROTTLE_CAN_ID (0x63) - /* * @brief Throttle report message (CAN frame) length. * */ #define OSCC_REPORT_THROTTLE_CAN_DLC (8) - /* * @brief Throttle report message publishing interval. [milliseconds] * */ #define OSCC_REPORT_THROTTLE_PUBLISH_INTERVAL_IN_MSEC (20) +/* + * @brief Number of throttle module DTCs. + * + */ +#define OSCC_THROTTLE_DTC_COUNT (1) + /** * @brief Throttle command message data. diff --git a/platforms/kia_soul/firmware/can_gateway/include/display.h b/platforms/kia_soul/firmware/can_gateway/include/display.h index cfa3aafc..d3155b38 100644 --- a/platforms/kia_soul/firmware/can_gateway/include/display.h +++ b/platforms/kia_soul/firmware/can_gateway/include/display.h @@ -9,6 +9,11 @@ #define _OSCC_KIA_SOUL_CAN_GATEWAY_DISPLAY_H_ +#include "brake_can_protocol.h" +#include "steering_can_protocol.h" +#include "throttle_can_protocol.h" + + /** * @brief Enumeration of possible screens. * @@ -16,7 +21,7 @@ typedef enum { STATUS_SCREEN, - ERROR_SCREEN, + DTC_SCREEN, SCREEN_COUNT } screen_t; @@ -61,13 +66,16 @@ typedef struct /** - * @brief Current error screen state. + * @brief Current DTC screen state. * */ typedef struct { - -} error_screen_s; + bool gateway[OSCC_GATEWAY_DTC_COUNT]; + bool brake[OSCC_BRAKE_DTC_COUNT]; + bool steering[OSCC_STEERING_DTC_COUNT]; + bool throttle[OSCC_THROTTLE_DTC_COUNT]; +} dtc_screen_s; /** @@ -78,7 +86,7 @@ typedef struct { screen_t current_screen; status_screen_s status_screen; - error_screen_s error_screen; + dtc_screen_s dtc_screen; } kia_soul_gateway_display_state_s; diff --git a/platforms/kia_soul/firmware/can_gateway/src/communications.cpp b/platforms/kia_soul/firmware/can_gateway/src/communications.cpp index 19fa3f90..e45dfe9b 100644 --- a/platforms/kia_soul/firmware/can_gateway/src/communications.cpp +++ b/platforms/kia_soul/firmware/can_gateway/src/communications.cpp @@ -78,6 +78,7 @@ void check_for_obd_timeout( void ) { bool timeout = false; + timeout = is_timeout( g_obd_steering_wheel_angle_rx_timestamp, GET_TIMESTAMP_MS(), @@ -88,8 +89,11 @@ void check_for_obd_timeout( void ) SET_HEARTBEAT_WARNING( KIA_SOUL_OBD_STEERING_WHEEL_ANGLE_HEARTBEAT_WARNING_BIT ); CLEAR_CHASSIS_1_FLAG( OSCC_REPORT_CHASSIS_STATE_1_FLAGS_BIT_STEER_WHEEL_ANGLE_VALID ); CLEAR_CHASSIS_1_FLAG( OSCC_REPORT_CHASSIS_STATE_1_FLAGS_BIT_STEER_WHEEL_ANGLE_RATE_VALID ); + + g_display_state.dtc_screen.gateway[0] = true; } + timeout = is_timeout( g_obd_wheel_speed_rx_timestamp, GET_TIMESTAMP_MS(), @@ -99,8 +103,11 @@ void check_for_obd_timeout( void ) { SET_HEARTBEAT_WARNING( KIA_SOUL_OBD_WHEEL_SPEED_HEARTBEAT_WARNING_BIT ); CLEAR_CHASSIS_1_FLAG( OSCC_REPORT_CHASSIS_STATE_1_FLAGS_BIT_WHEEL_SPEED_VALID ); + + g_display_state.dtc_screen.gateway[1] = true; } + timeout = is_timeout( g_obd_brake_pressure_rx_timestamp, GET_TIMESTAMP_MS(), @@ -110,8 +117,11 @@ void check_for_obd_timeout( void ) { SET_HEARTBEAT_WARNING( KIA_SOUL_OBD_BRAKE_PRESSURE_WARNING_BIT ); CLEAR_CHASSIS_1_FLAG( OSCC_REPORT_CHASSIS_STATE_1_FLAGS_BIT_BRAKE_PRESSURE_VALID ); + + g_display_state.dtc_screen.gateway[2] = true; } + timeout = is_timeout( g_obd_turn_signal_rx_timestamp, GET_TIMESTAMP_MS(), @@ -123,6 +133,17 @@ void check_for_obd_timeout( void ) CLEAR_CHASSIS_1_FLAG( OSCC_REPORT_CHASSIS_STATE_1_FLAGS_BIT_LEFT_TURN_SIGNAL_ON ); CLEAR_CHASSIS_1_FLAG( OSCC_REPORT_CHASSIS_STATE_1_FLAGS_BIT_RIGHT_TURN_SIGNAL_ON ); CLEAR_CHASSIS_1_FLAG( OSCC_REPORT_CHASSIS_STATE_1_FLAGS_BIT_BRAKE_SIGNAL_ON ); + + g_display_state.dtc_screen.gateway[3] = true; + } + + + if( g_display_state.dtc_screen.gateway[0] + || g_display_state.dtc_screen.gateway[1] + || g_display_state.dtc_screen.gateway[2] + || g_display_state.dtc_screen.gateway[3] ) + { + g_display_state.status_screen.gateway = GATEWAY_STATUS_WARNING; } } @@ -201,6 +222,8 @@ static void process_obd_steering_wheel_angle( g_tx_chassis_state_1.data.steering_wheel_angle_rate = 0; g_tx_chassis_state_1.data.steering_wheel_angle = steering_wheel_angle_data->steering_angle; + g_display_state.dtc_screen.gateway[0] = false; + g_obd_steering_wheel_angle_rx_timestamp = GET_TIMESTAMP_MS( ); } } @@ -222,6 +245,8 @@ static void process_obd_wheel_speed( g_tx_chassis_state_2.data.wheel_speed_rear_left = wheel_speed_data->wheel_speed_rear_left; g_tx_chassis_state_2.data.wheel_speed_rear_right = wheel_speed_data->wheel_speed_rear_right; + g_display_state.dtc_screen.gateway[1] = false; + g_obd_wheel_speed_rx_timestamp = GET_TIMESTAMP_MS( ); } } @@ -240,6 +265,8 @@ static void process_obd_brake_pressure( g_tx_chassis_state_1.data.brake_pressure = brake_pressure_data->master_cylinder_pressure; + g_display_state.dtc_screen.gateway[2] = false; + g_obd_brake_pressure_rx_timestamp = GET_TIMESTAMP_MS( ); } } @@ -267,6 +294,8 @@ static void process_obd_turn_signal( SET_CHASSIS_1_FLAG( OSCC_REPORT_CHASSIS_STATE_1_FLAGS_BIT_RIGHT_TURN_SIGNAL_ON ); } + g_display_state.dtc_screen.gateway[3] = false; + g_obd_turn_signal_rx_timestamp = GET_TIMESTAMP_MS( ); } } @@ -288,6 +317,26 @@ static void process_brake_report( { g_display_state.status_screen.brakes = MODULE_STATUS_DISABLED; } + + g_display_state.dtc_screen.brake[0] = + brake_report_data->dtc00_invalid_sensor_value; + + g_display_state.dtc_screen.brake[1] = + brake_report_data->dtc01_obd_timeout; + + g_display_state.dtc_screen.brake[2] = + brake_report_data->dtc02_startup_pressure_check_error; + + g_display_state.dtc_screen.brake[3] = + brake_report_data->dtc03_startup_pump_motor_check_error; + + if( g_display_state.dtc_screen.brake[0] + || g_display_state.dtc_screen.brake[1] + || g_display_state.dtc_screen.brake[2] + || g_display_state.dtc_screen.brake[3] ) + { + g_display_state.status_screen.brakes = MODULE_STATUS_ERROR; + } } } @@ -308,6 +357,18 @@ static void process_steering_report( { g_display_state.status_screen.steering = MODULE_STATUS_DISABLED; } + + g_display_state.dtc_screen.steering[0] = + steering_report_data->dtc00_invalid_sensor_value; + + g_display_state.dtc_screen.steering[1] = + steering_report_data->dtc01_obd_timeout; + + if( g_display_state.dtc_screen.steering[0] + || g_display_state.dtc_screen.steering[1] ) + { + g_display_state.status_screen.steering = MODULE_STATUS_ERROR; + } } } @@ -329,6 +390,14 @@ static void process_throttle_report( { g_display_state.status_screen.throttle = MODULE_STATUS_DISABLED; } + + g_display_state.dtc_screen.throttle[0] = + throttle_report_data->dtc00_invalid_sensor_value; + + if( g_display_state.dtc_screen.throttle[0] ) + { + g_display_state.status_screen.throttle = MODULE_STATUS_ERROR; + } } } diff --git a/platforms/kia_soul/firmware/can_gateway/src/display.cpp b/platforms/kia_soul/firmware/can_gateway/src/display.cpp index 70f742ea..e5317095 100644 --- a/platforms/kia_soul/firmware/can_gateway/src/display.cpp +++ b/platforms/kia_soul/firmware/can_gateway/src/display.cpp @@ -5,10 +5,56 @@ #include "globals.h" #include "debug.h" +#include "brake_can_protocol.h" +#include "steering_can_protocol.h" +#include "throttle_can_protocol.h" #include "display.h" +/* + * @brief Pixel position of the display's X origin. + * + */ +#define ORIGIN_X_POS ( 0 ) + +/* + * @brief Pixel position of the display's Y origin. + * + */ +#define ORIGIN_Y_POS ( 0 ) + +/* + * @brief X pixel position of the DTC screen's gateway column. + * + */ +#define GATEWAY_DTC_X_POS ( 0 ) + +/* + * @brief X pixel position of the DTC screen's brake column. + * + */ +#define BRAKE_DTC_X_POS ( 33 ) + +/* + * @brief X pixel position of the DTC screen's steering column. + * + */ +#define STEERING_DTC_X_POS ( 66 ) + +/* + * @brief X pixel position of the DTC screen's throttle column. + * + */ +#define THROTTLE_DTC_X_POS ( 99 ) + +/* + * @brief Pixel height of a character on the display. + * + */ +#define CHARACTER_HEIGHT ( 10 ) + + static const char * gateway_status_strings[] = { "UNKNOWN", @@ -28,14 +74,20 @@ static const char * module_status_strings[] = static void read_button( void ); static void display_status_screen( void ); -static void display_error_screen( void ); +static void display_dtc_screen( void ); static void print_gateway_status( gateway_status_t status ); static void print_module_status( module_status_t status ); +static void print_gateway_dtcs( void ); +static void print_brake_dtcs( void ); +static void print_steering_dtcs( void ); +static void print_throttle_dtcs( void ); +static void print_dtc( const char *type, int num ); +static void print_padded_number( const unsigned int number ); void update_display( void ) { - g_display.setCursor( 0, 0 ); + g_display.setCursor( ORIGIN_X_POS, ORIGIN_Y_POS ); g_display.setTextColor( WHITE, BLACK ); read_button( ); @@ -44,9 +96,9 @@ void update_display( void ) { display_status_screen( ); } - else if( g_display_state.current_screen == ERROR_SCREEN ) + else if( g_display_state.current_screen == DTC_SCREEN ) { - display_error_screen( ); + display_dtc_screen( ); } } @@ -83,16 +135,34 @@ static void display_status_screen( void ) } -static void display_error_screen( void ) +static void display_dtc_screen( void ) { g_display.eraseBuffer( ); - g_display.print( "Errors\n" ); + if( (g_display_state.status_screen.gateway == GATEWAY_STATUS_ERROR) + || (g_display_state.status_screen.gateway == GATEWAY_STATUS_WARNING) ) + { + print_gateway_dtcs( ); + } + + if( g_display_state.status_screen.brakes == MODULE_STATUS_ERROR ) + { + print_brake_dtcs( ); + } + + if( g_display_state.status_screen.steering == MODULE_STATUS_ERROR ) + { + print_steering_dtcs( ); + } + + if( g_display_state.status_screen.throttle == MODULE_STATUS_ERROR ) + { + print_throttle_dtcs( ); + } g_display.sendBuffer( ); } - static void print_gateway_status( gateway_status_t status ) { const char * status_string = gateway_status_strings[status]; @@ -129,3 +199,92 @@ static void print_module_status( module_status_t status ) g_display.print( "\n\n" ); } + +static void print_gateway_dtcs( void ) +{ + g_display.setCursor( GATEWAY_DTC_X_POS, ORIGIN_Y_POS ); + + for( int dtc = 0; dtc < OSCC_GATEWAY_DTC_COUNT; ++dtc ) + { + if( g_display_state.dtc_screen.gateway[dtc] == true ) + { + print_dtc( "P1G", dtc ); + } + + g_display.setCursor( + GATEWAY_DTC_X_POS, + (CHARACTER_HEIGHT + (dtc * CHARACTER_HEIGHT)) ); + } +} + + +static void print_brake_dtcs( void ) +{ + g_display.setCursor( BRAKE_DTC_X_POS, ORIGIN_Y_POS ); + + for( int dtc = 0; dtc < OSCC_BRAKE_DTC_COUNT; ++dtc ) + { + if( g_display_state.dtc_screen.brake[dtc] == true ) + { + print_dtc( "P1B", dtc ); + } + + g_display.setCursor( + BRAKE_DTC_X_POS, + (CHARACTER_HEIGHT + (dtc * CHARACTER_HEIGHT)) ); + } +} + + +static void print_steering_dtcs( void ) +{ + g_display.setCursor( STEERING_DTC_X_POS, ORIGIN_Y_POS ) ; + + for( int dtc = 0; dtc < OSCC_STEERING_DTC_COUNT; ++dtc ) + { + if( g_display_state.dtc_screen.steering[dtc] == true ) + { + print_dtc( "P1S", dtc ); + } + + g_display.setCursor( + STEERING_DTC_X_POS, + (CHARACTER_HEIGHT + (dtc * CHARACTER_HEIGHT)) ); + } +} + + +static void print_throttle_dtcs( void ) +{ + g_display.setCursor( THROTTLE_DTC_X_POS, ORIGIN_Y_POS ); + + for( int dtc = 0; dtc < OSCC_THROTTLE_DTC_COUNT; ++dtc ) + { + if( g_display_state.dtc_screen.throttle[dtc] == true ) + { + print_dtc( "P1T", dtc ); + } + + g_display.setCursor( + THROTTLE_DTC_X_POS, + (CHARACTER_HEIGHT + (dtc * CHARACTER_HEIGHT)) ); + } +} + + +static void print_dtc( const char *type, int num ) +{ + g_display.print( type ); + print_padded_number( num ); +} + + +static void print_padded_number( const unsigned int number ) +{ + if( number < 10 ) + { + g_display.print( "0" ); + } + + g_display.print( number ); +} From f00b9dc12e9b721561756fb96dd5c2e31581d469 Mon Sep 17 00:00:00 2001 From: Austin Morlan Date: Fri, 30 Jun 2017 16:17:14 -0700 Subject: [PATCH 07/84] Move read_button to bottom of file --- .../firmware/can_gateway/src/display.cpp | 28 ++++++++++--------- 1 file changed, 15 insertions(+), 13 deletions(-) diff --git a/platforms/kia_soul/firmware/can_gateway/src/display.cpp b/platforms/kia_soul/firmware/can_gateway/src/display.cpp index e5317095..e393c3cb 100644 --- a/platforms/kia_soul/firmware/can_gateway/src/display.cpp +++ b/platforms/kia_soul/firmware/can_gateway/src/display.cpp @@ -72,7 +72,6 @@ static const char * module_status_strings[] = }; -static void read_button( void ); static void display_status_screen( void ); static void display_dtc_screen( void ); static void print_gateway_status( gateway_status_t status ); @@ -83,6 +82,7 @@ static void print_steering_dtcs( void ); static void print_throttle_dtcs( void ); static void print_dtc( const char *type, int num ); static void print_padded_number( const unsigned int number ); +static void read_button( void ); void update_display( void ) @@ -103,18 +103,6 @@ void update_display( void ) } -static void read_button( void ) -{ - int button_val = digitalRead( PIN_DISPLAY_BUTTON_STATUS ); - - if( button_val == 1 ) - { - g_display_state.current_screen = - (screen_t)((g_display_state.current_screen + 1) % SCREEN_COUNT); - } -} - - static void display_status_screen( void ) { g_display.eraseBuffer(); @@ -163,6 +151,7 @@ static void display_dtc_screen( void ) g_display.sendBuffer( ); } + static void print_gateway_status( gateway_status_t status ) { const char * status_string = gateway_status_strings[status]; @@ -200,6 +189,7 @@ static void print_module_status( module_status_t status ) g_display.print( "\n\n" ); } + static void print_gateway_dtcs( void ) { g_display.setCursor( GATEWAY_DTC_X_POS, ORIGIN_Y_POS ); @@ -288,3 +278,15 @@ static void print_padded_number( const unsigned int number ) g_display.print( number ); } + + +static void read_button( void ) +{ + int button_val = digitalRead( PIN_DISPLAY_BUTTON_STATUS ); + + if( button_val == 1 ) + { + g_display_state.current_screen = + (screen_t)((g_display_state.current_screen + 1) % SCREEN_COUNT); + } +} From 4cb19aaf018add2b1057a6c7eeff715a55c00ae7 Mon Sep 17 00:00:00 2001 From: Austin Morlan Date: Wed, 5 Jul 2017 10:04:21 -0700 Subject: [PATCH 08/84] Rename display button macro --- .../kia_soul/firmware/can_gateway/include/globals.h | 10 ++-------- .../kia_soul/firmware/can_gateway/src/display.cpp | 2 +- 2 files changed, 3 insertions(+), 9 deletions(-) diff --git a/platforms/kia_soul/firmware/can_gateway/include/globals.h b/platforms/kia_soul/firmware/can_gateway/include/globals.h index 56ad3e22..7ad371b2 100644 --- a/platforms/kia_soul/firmware/can_gateway/include/globals.h +++ b/platforms/kia_soul/firmware/can_gateway/include/globals.h @@ -60,16 +60,10 @@ #define PIN_DISPLAY_DC ( 5 ) /* - * @brief Pin of display status screen button. + * @brief Pin of display button. * */ -#define PIN_DISPLAY_BUTTON_STATUS ( 4 ) - -/* - * @brief Pin of display error screen button. - * - */ -#define PIN_DISPLAY_BUTTON_ERROR ( 3 ) +#define PIN_DISPLAY_BUTTON ( 4 ) #ifdef GLOBAL_DEFINED diff --git a/platforms/kia_soul/firmware/can_gateway/src/display.cpp b/platforms/kia_soul/firmware/can_gateway/src/display.cpp index e393c3cb..f01ae7c9 100644 --- a/platforms/kia_soul/firmware/can_gateway/src/display.cpp +++ b/platforms/kia_soul/firmware/can_gateway/src/display.cpp @@ -282,7 +282,7 @@ static void print_padded_number( const unsigned int number ) static void read_button( void ) { - int button_val = digitalRead( PIN_DISPLAY_BUTTON_STATUS ); + int button_val = digitalRead( PIN_DISPLAY_BUTTON ); if( button_val == 1 ) { From dbe64595003a341d224c288e55d12d17d5004bf9 Mon Sep 17 00:00:00 2001 From: Austin Morlan Date: Thu, 6 Jul 2017 11:08:42 -0700 Subject: [PATCH 09/84] Check for control CAN frames on control CAN bus --- .../can_gateway/src/communications.cpp | 33 ++++++++++++++----- 1 file changed, 25 insertions(+), 8 deletions(-) diff --git a/platforms/kia_soul/firmware/can_gateway/src/communications.cpp b/platforms/kia_soul/firmware/can_gateway/src/communications.cpp index e45dfe9b..9ea6d705 100644 --- a/platforms/kia_soul/firmware/can_gateway/src/communications.cpp +++ b/platforms/kia_soul/firmware/can_gateway/src/communications.cpp @@ -46,7 +46,10 @@ static void process_steering_report( static void process_throttle_report( const uint8_t * const data ); -static void process_rx_frame( +static void process_obd_frame( + const can_frame_s * const rx_frame ); + +static void process_control_frame( const can_frame_s * const rx_frame ); @@ -150,12 +153,18 @@ void check_for_obd_timeout( void ) void check_for_incoming_message( void ) { - can_frame_s rx_frame; - can_status_t ret = check_for_rx_frame( g_obd_can, &rx_frame ); + can_frame_s obd_frame; + can_status_t obd_frame_availability = check_for_rx_frame( g_obd_can, &obd_frame ); + if( obd_frame_availability == CAN_RX_FRAME_AVAILABLE ) + { + process_obd_frame( &obd_frame ); + } - if( ret == CAN_RX_FRAME_AVAILABLE ) + can_frame_s control_frame; + can_status_t control_frame_availability = check_for_rx_frame( g_control_can, &control_frame ); + if( control_frame_availability == CAN_RX_FRAME_AVAILABLE ) { - process_rx_frame( &rx_frame ); + process_control_frame( &control_frame ); } } @@ -402,8 +411,7 @@ static void process_throttle_report( } - -static void process_rx_frame( +static void process_obd_frame( const can_frame_s * const rx_frame ) { if ( rx_frame != NULL ) @@ -424,7 +432,16 @@ static void process_rx_frame( { process_obd_turn_signal( rx_frame->data ); } - else if( rx_frame->id == OSCC_REPORT_BRAKE_CAN_ID ) + } +} + + +static void process_control_frame( + const can_frame_s * const rx_frame ) +{ + if ( rx_frame != NULL ) + { + if( rx_frame->id == OSCC_REPORT_BRAKE_CAN_ID ) { process_brake_report( rx_frame->data ); } From e161ab6cd1c289f8867555da97559d1991f89b03 Mon Sep 17 00:00:00 2001 From: Austin Morlan Date: Thu, 6 Jul 2017 11:27:50 -0700 Subject: [PATCH 10/84] Optimize SSD1325 library for speed Prior to this commit, the SSD1325 library set the CS lines for each byte rather than a block of bytes which caused slowdown in the overall speed of the main while loop. This commit modifies the SSD1325 library to assert its CS pin before a block of successive SPI transfers and then deassert afterward. --- platforms/common/libs/ssd1325/ssd1325.cpp | 274 ++++++++++++---------- platforms/common/libs/ssd1325/ssd1325.h | 9 +- 2 files changed, 161 insertions(+), 122 deletions(-) diff --git a/platforms/common/libs/ssd1325/ssd1325.cpp b/platforms/common/libs/ssd1325/ssd1325.cpp index 3c9554bc..4c471d55 100644 --- a/platforms/common/libs/ssd1325/ssd1325.cpp +++ b/platforms/common/libs/ssd1325/ssd1325.cpp @@ -94,138 +94,174 @@ static uint8_t buffer[SSD1325_LCDHEIGHT * SSD1325_LCDWIDTH / 8] = { }; -void SSD1325::begin(void) { - SPI.begin(); - SPI.setDataMode(SPI_MODE0); - SPI.setClockDivider(SPI_CLOCK_DIV2); - - pinMode(dc, OUTPUT); - pinMode(rst, OUTPUT); - pinMode(cs, OUTPUT); - - digitalWrite(rst, HIGH); - // VDD (3.3V) goes high at start, lets just chill for a ms - delay(1); - // bring reset low - digitalWrite(rst, LOW); - // wait 10ms - delay(10); - // bring out of reset - digitalWrite(rst, HIGH); - - delay(500); - - sendCommand(SSD1325_DISPLAYOFF); /* display off */ - sendCommand(SSD1325_SETCLOCK); /* set osc division */ - sendCommand(0xF1); /* 145 */ - sendCommand(SSD1325_SETMULTIPLEX ); /* multiplex ratio */ - sendCommand(0x3f); /* duty = 1/64 */ - sendCommand( SSD1325_SETOFFSET); /* set display offset --- */ - sendCommand(0x4C); /* 76 */ - sendCommand(SSD1325_SETSTARTLINE); /*set start line */ - sendCommand(0x00); /* ------ */ - sendCommand(SSD1325_MASTERCONFIG); /*Set Master Config DC/DC Converter*/ - sendCommand(0x02); - sendCommand(SSD1325_SETREMAP); /* set segment remap------ */ - sendCommand(0x56); - sendCommand(SSD1325_SETCURRENT + 0x1); /* Set Current Range */ - sendCommand(SSD1325_SETGRAYTABLE); - sendCommand(0x01); - sendCommand(0x11); - sendCommand(0x22); - sendCommand(0x32); - sendCommand(0x43); - sendCommand(0x54); - sendCommand(0x65); - sendCommand(0x76); - sendCommand(SSD1325_SETCONTRAST); /* set contrast current */ - sendCommand(0x7F); // max! - sendCommand(SSD1325_SETROWPERIOD); - sendCommand(0x51); - sendCommand(SSD1325_SETPHASELEN); - sendCommand(0x55); - sendCommand(SSD1325_SETPRECHARGECOMP); - sendCommand(0x02); - sendCommand(SSD1325_SETPRECHARGECOMPENABLE); - sendCommand(0x28); - sendCommand(SSD1325_SETVCOMLEVEL); // Set High Voltage Level of COM Pin - sendCommand(0x1C); //? - sendCommand(SSD1325_SETVSL); // set Low Voltage Level of SEG Pin - sendCommand(0x0D|0x02); - - sendCommand(SSD1325_NORMALDISPLAY); /* set display mode */ - - sendCommand(SSD1325_DISPLAYON); /* display ON */ +void SSD1325::begin(void) +{ + SPI.begin(); + SPI.setDataMode(SPI_MODE0); + SPI.setClockDivider(SPI_CLOCK_DIV2); + + pinMode(dc, OUTPUT); + pinMode(rst, OUTPUT); + pinMode(cs, OUTPUT); + + digitalWrite(rst, HIGH); + // VDD (3.3V) goes high at start, lets just chill for a ms + delay(1); + // bring reset low + digitalWrite(rst, LOW); + // wait 10ms + delay(10); + // bring out of reset + digitalWrite(rst, HIGH); + + delay(500); + + startSendCommand(); + SPI.transfer(SSD1325_DISPLAYOFF); /* display off */ + SPI.transfer(SSD1325_SETCLOCK); /* set osc division */ + SPI.transfer(0xF1); /* 145 */ + SPI.transfer(SSD1325_SETMULTIPLEX ); /* multiplex ratio */ + SPI.transfer(0x3f); /* duty = 1/64 */ + SPI.transfer( SSD1325_SETOFFSET); /* set display offset --- */ + SPI.transfer(0x4C); /* 76 */ + SPI.transfer(SSD1325_SETSTARTLINE); /*set start line */ + SPI.transfer(0x00); /* ------ */ + SPI.transfer(SSD1325_MASTERCONFIG); /*Set Master Config DC/DC Converter*/ + SPI.transfer(0x02); + SPI.transfer(SSD1325_SETREMAP); /* set segment remap------ */ + SPI.transfer(0x56); + SPI.transfer(SSD1325_SETCURRENT + 0x1); /* Set Current Range */ + SPI.transfer(SSD1325_SETGRAYTABLE); + SPI.transfer(0x01); + SPI.transfer(0x11); + SPI.transfer(0x22); + SPI.transfer(0x32); + SPI.transfer(0x43); + SPI.transfer(0x54); + SPI.transfer(0x65); + SPI.transfer(0x76); + SPI.transfer(SSD1325_SETCONTRAST); /* set contrast current */ + SPI.transfer(0x7F); // max! + SPI.transfer(SSD1325_SETROWPERIOD); + SPI.transfer(0x51); + SPI.transfer(SSD1325_SETPHASELEN); + SPI.transfer(0x55); + SPI.transfer(SSD1325_SETPRECHARGECOMP); + SPI.transfer(0x02); + SPI.transfer(SSD1325_SETPRECHARGECOMPENABLE); + SPI.transfer(0x28); + SPI.transfer(SSD1325_SETVCOMLEVEL); // Set High Voltage Level of COM Pin + SPI.transfer(0x1C); //? + SPI.transfer(SSD1325_SETVSL); // set Low Voltage Level of SEG Pin + SPI.transfer(0x0D|0x02); + SPI.transfer(SSD1325_NORMALDISPLAY); /* set display mode */ + SPI.transfer(0x15); /* set column address */ + SPI.transfer(0x00); /* set column start address */ + SPI.transfer(0x3f); /* set column end address */ + SPI.transfer(0x75); /* set row address */ + SPI.transfer(0x00); /* set row start address */ + SPI.transfer(0x3f); /* set row end address */ + SPI.transfer(SSD1325_DISPLAYON); /* display ON */ + stopSendCommand(); } -void SSD1325::sendBuffer(void) { - sendCommand(0x15); /* set column address */ - sendCommand(0x00); /* set column start address */ - sendCommand(0x3f); /* set column end address */ - sendCommand(0x75); /* set row address */ - sendCommand(0x00); /* set row start address */ - sendCommand(0x3f); /* set row end address */ - delay(1); - - for (uint16_t x=0; x<128; x+=2) { - for (uint16_t y=0; y<64; y+=8) { // we write 8 pixels at once - uint8_t left8 = buffer[y*16+x]; - uint8_t right8 = buffer[y*16+x+1]; - for (uint8_t p=0; p<8; p++) { - uint8_t d = 0; - if (left8 & (1 << p)) d |= 0xF0; - if (right8 & (1 << p)) d |= 0x0F; - sendData(d); - } +void SSD1325::sendBuffer(void) +{ + startSendData(); + + for (uint16_t x=0; x<128; x+=2) + { + for (uint16_t y=0; y<64; y+=8) + { // we write 8 pixels at once + uint8_t left8 = buffer[y*16+x]; + uint8_t right8 = buffer[y*16+x+1]; + + for (uint8_t p=0; p<8; p++) + { + uint8_t d = 0; + + if (left8 & (1 << p)) + { + d |= 0xF0; + }; + + if (right8 & (1 << p)) + { + d |= 0x0F; + } + + SPI.transfer(d); + } + } } - } + + stopSendData(); } -void SSD1325::eraseBuffer(void) { - memset(buffer, 0, sizeof(buffer)); +void SSD1325::eraseBuffer(void) +{ + memset(buffer, 0, sizeof(buffer)); } -void SSD1325::sendCommand(uint8_t c) { - digitalWrite(dc, LOW); - digitalWrite(cs, LOW); - SPI.transfer(c); - digitalWrite(cs, HIGH); +void SSD1325::startSendCommand(void) +{ + digitalWrite(dc, LOW); + digitalWrite(cs, LOW); } -void SSD1325::sendData(uint8_t c) { - digitalWrite(dc, HIGH); - digitalWrite(cs, LOW); - SPI.transfer(c); - digitalWrite(cs, HIGH); +void SSD1325::stopSendCommand(void) +{ + digitalWrite(cs, HIGH); + digitalWrite(dc, HIGH); } +void SSD1325::startSendData(void) +{ + digitalWrite(dc, HIGH); + digitalWrite(cs, LOW); +} + +void SSD1325::stopSendData(void) +{ + digitalWrite(cs, HIGH); + digitalWrite(dc, LOW); +} + + +void SSD1325::drawPixel(int16_t x, int16_t y, uint16_t color) +{ + if ((x >= width()) || (y >= height()) || (x < 0) || (y < 0)) + { + return; + } + + // check rotation, move pixel around if necessary + switch (getRotation()) + { + case 1: + adagfx_swap(x, y); + x = WIDTH - x - 1; + break; + case 2: + x = WIDTH - x - 1; + y = HEIGHT - y - 1; + break; + case 3: + adagfx_swap(x, y); + y = HEIGHT - y - 1; + break; + } -void SSD1325::drawPixel(int16_t x, int16_t y, uint16_t color) { - if ((x >= width()) || (y >= height()) || (x < 0) || (y < 0)) - return; - - // check rotation, move pixel around if necessary - switch (getRotation()) { - case 1: - adagfx_swap(x, y); - x = WIDTH - x - 1; - break; - case 2: - x = WIDTH - x - 1; - y = HEIGHT - y - 1; - break; - case 3: - adagfx_swap(x, y); - y = HEIGHT - y - 1; - break; - } - - // x is which column - if (color == WHITE) - buffer[x+ (y/8)*SSD1325_LCDWIDTH] |= _BV((y%8)); - else - buffer[x+ (y/8)*SSD1325_LCDWIDTH] &= ~_BV((y%8)); + // x is which column + if (color == WHITE) + { + buffer[x+ (y/8)*SSD1325_LCDWIDTH] |= _BV((y%8)); + } + else + { + buffer[x+ (y/8)*SSD1325_LCDWIDTH] &= ~_BV((y%8)); + } } diff --git a/platforms/common/libs/ssd1325/ssd1325.h b/platforms/common/libs/ssd1325/ssd1325.h index 1ca57209..630b6d46 100644 --- a/platforms/common/libs/ssd1325/ssd1325.h +++ b/platforms/common/libs/ssd1325/ssd1325.h @@ -76,7 +76,7 @@ class SSD1325 : public GFX { void begin(void); void eraseBuffer(void); - void sendBuffer(); + void sendBuffer(void); private: int8_t sid; @@ -85,7 +85,10 @@ class SSD1325 : public GFX { int8_t rst; int8_t cs; - void sendCommand(uint8_t c); - void sendData(uint8_t c); + void startSendCommand(void); + void stopSendCommand(void); + void startSendData(void); + void stopSendData(void); + void drawPixel(int16_t x, int16_t y, uint16_t color); }; From 898712a64a667aa9871abc6102d12fc98045a8ab Mon Sep 17 00:00:00 2001 From: Austin Morlan Date: Thu, 6 Jul 2017 11:51:51 -0700 Subject: [PATCH 11/84] Add timer for display updating Prior to this commit, the display was updated once every time through the loop which exceeded the processing power of the Arduino and caused CAN frames to be received from OBD at such a slow pace that they were considered to have timed out. This commit adds a timer to the display update logic to only update every 250 milliseconds. --- .../firmware/can_gateway/src/display.cpp | 40 ++++++++++++++----- 1 file changed, 31 insertions(+), 9 deletions(-) diff --git a/platforms/kia_soul/firmware/can_gateway/src/display.cpp b/platforms/kia_soul/firmware/can_gateway/src/display.cpp index f01ae7c9..0440ac30 100644 --- a/platforms/kia_soul/firmware/can_gateway/src/display.cpp +++ b/platforms/kia_soul/firmware/can_gateway/src/display.cpp @@ -8,6 +8,7 @@ #include "brake_can_protocol.h" #include "steering_can_protocol.h" #include "throttle_can_protocol.h" +#include "oscc_time.h" #include "display.h" @@ -54,6 +55,12 @@ */ #define CHARACTER_HEIGHT ( 10 ) +/* + * @brief Amount of time between updates of display content. [milliseconds] + * + */ +#define DISPLAY_UPDATE_INTERVAL_IN_MS ( 250 ) + static const char * gateway_status_strings[] = { @@ -87,18 +94,33 @@ static void read_button( void ); void update_display( void ) { - g_display.setCursor( ORIGIN_X_POS, ORIGIN_Y_POS ); - g_display.setTextColor( WHITE, BLACK ); + static unsigned long last_update_time = 0; - read_button( ); + bool timeout = false; + unsigned long current_time = GET_TIMESTAMP_MS(); - if( g_display_state.current_screen == STATUS_SCREEN ) - { - display_status_screen( ); - } - else if( g_display_state.current_screen == DTC_SCREEN ) + timeout = is_timeout( + last_update_time, + current_time, + DISPLAY_UPDATE_INTERVAL_IN_MS ); + + if ( timeout == true ) { - display_dtc_screen( ); + last_update_time = current_time; + + g_display.setCursor( ORIGIN_X_POS, ORIGIN_Y_POS ); + g_display.setTextColor( WHITE, BLACK ); + + read_button( ); + + if( g_display_state.current_screen == STATUS_SCREEN ) + { + display_status_screen( ); + } + else if( g_display_state.current_screen == DTC_SCREEN ) + { + display_dtc_screen( ); + } } } From 5362a8dcbbc518207b2d56b090f86e14eff47b3d Mon Sep 17 00:00:00 2001 From: Austin Morlan Date: Thu, 6 Jul 2017 12:46:43 -0700 Subject: [PATCH 12/84] Add display status LED logic --- .../firmware/can_gateway/include/display.h | 13 ++++ .../firmware/can_gateway/include/globals.h | 18 +++++ .../can_gateway/src/communications.cpp | 6 +- .../firmware/can_gateway/src/display.cpp | 68 +++++++++++++++++++ .../firmware/can_gateway/src/init.cpp | 5 +- 5 files changed, 107 insertions(+), 3 deletions(-) diff --git a/platforms/kia_soul/firmware/can_gateway/include/display.h b/platforms/kia_soul/firmware/can_gateway/include/display.h index d3155b38..06b1158f 100644 --- a/platforms/kia_soul/firmware/can_gateway/include/display.h +++ b/platforms/kia_soul/firmware/can_gateway/include/display.h @@ -90,6 +90,19 @@ typedef struct } kia_soul_gateway_display_state_s; +// **************************************************************************** +// Function: init_display +// +// Purpose: Initializes the display. +// +// Returns: void +// +// Parameters: void +// +// **************************************************************************** +void init_display( void ); + + // **************************************************************************** // Function: update_display // diff --git a/platforms/kia_soul/firmware/can_gateway/include/globals.h b/platforms/kia_soul/firmware/can_gateway/include/globals.h index 7ad371b2..0f089aca 100644 --- a/platforms/kia_soul/firmware/can_gateway/include/globals.h +++ b/platforms/kia_soul/firmware/can_gateway/include/globals.h @@ -65,6 +65,24 @@ */ #define PIN_DISPLAY_BUTTON ( 4 ) +/* + * @brief Pin of good (green) display LED. + * + */ +#define PIN_DISPLAY_LED_GOOD ( 8 ) + +/* + * @brief Pin of warning (yellow) display LED. + * + */ +#define PIN_DISPLAY_LED_WARNING ( 3 ) + +/* + * @brief Pin of error (red) display LED. + * + */ +#define PIN_DISPLAY_LED_ERROR ( 2 ) + #ifdef GLOBAL_DEFINED MCP_CAN g_obd_can( PIN_OBD_CAN_CHIP_SELECT ); diff --git a/platforms/kia_soul/firmware/can_gateway/src/communications.cpp b/platforms/kia_soul/firmware/can_gateway/src/communications.cpp index 9ea6d705..fe028150 100644 --- a/platforms/kia_soul/firmware/can_gateway/src/communications.cpp +++ b/platforms/kia_soul/firmware/can_gateway/src/communications.cpp @@ -146,7 +146,11 @@ void check_for_obd_timeout( void ) || g_display_state.dtc_screen.gateway[2] || g_display_state.dtc_screen.gateway[3] ) { - g_display_state.status_screen.gateway = GATEWAY_STATUS_WARNING; + g_display_state.status_screen.gateway = GATEWAY_STATUS_ERROR; + } + else + { + g_display_state.status_screen.gateway = GATEWAY_STATUS_GOOD; } } diff --git a/platforms/kia_soul/firmware/can_gateway/src/display.cpp b/platforms/kia_soul/firmware/can_gateway/src/display.cpp index 0440ac30..1ad1827f 100644 --- a/platforms/kia_soul/firmware/can_gateway/src/display.cpp +++ b/platforms/kia_soul/firmware/can_gateway/src/display.cpp @@ -81,6 +81,7 @@ static const char * module_status_strings[] = static void display_status_screen( void ); static void display_dtc_screen( void ); +static void update_leds( ); static void print_gateway_status( gateway_status_t status ); static void print_module_status( module_status_t status ); static void print_gateway_dtcs( void ); @@ -90,10 +91,30 @@ static void print_throttle_dtcs( void ); static void print_dtc( const char *type, int num ); static void print_padded_number( const unsigned int number ); static void read_button( void ); +static void enable_good_led( void ); +static void enable_warning_led( void ); +static void enable_error_led( void ); + + +void init_display( void ) +{ + digitalWrite(PIN_DISPLAY_LED_GOOD, LOW); + digitalWrite(PIN_DISPLAY_LED_WARNING, LOW); + digitalWrite(PIN_DISPLAY_LED_ERROR, LOW); + + pinMode(PIN_DISPLAY_LED_GOOD, OUTPUT); + pinMode(PIN_DISPLAY_LED_WARNING, OUTPUT); + pinMode(PIN_DISPLAY_LED_ERROR, OUTPUT); + + g_display.begin(); +} void update_display( void ) { + update_leds( ); + + static unsigned long last_update_time = 0; bool timeout = false; @@ -125,6 +146,29 @@ void update_display( void ) } +static void update_leds( void ) +{ + if( (g_display_state.status_screen.gateway == GATEWAY_STATUS_ERROR) + || (g_display_state.status_screen.brakes == MODULE_STATUS_ERROR) + || (g_display_state.status_screen.steering == MODULE_STATUS_ERROR) + || (g_display_state.status_screen.throttle == MODULE_STATUS_ERROR) ) + { + enable_error_led( ); + } + else if( (g_display_state.status_screen.gateway == GATEWAY_STATUS_WARNING) + || (g_display_state.status_screen.brakes == MODULE_STATUS_UNKNOWN) + || (g_display_state.status_screen.steering == MODULE_STATUS_UNKNOWN) + || (g_display_state.status_screen.throttle == MODULE_STATUS_UNKNOWN) ) + { + enable_warning_led( ); + } + else + { + enable_good_led( ); + } +} + + static void display_status_screen( void ) { g_display.eraseBuffer(); @@ -312,3 +356,27 @@ static void read_button( void ) (screen_t)((g_display_state.current_screen + 1) % SCREEN_COUNT); } } + + +static void enable_good_led( void ) +{ + digitalWrite(PIN_DISPLAY_LED_GOOD, HIGH); + digitalWrite(PIN_DISPLAY_LED_WARNING, LOW); + digitalWrite(PIN_DISPLAY_LED_ERROR, LOW); +} + + +static void enable_warning_led( void ) +{ + digitalWrite(PIN_DISPLAY_LED_GOOD, LOW); + digitalWrite(PIN_DISPLAY_LED_WARNING, HIGH); + digitalWrite(PIN_DISPLAY_LED_ERROR, LOW); +} + + +static void enable_error_led( void ) +{ + digitalWrite(PIN_DISPLAY_LED_GOOD, LOW); + digitalWrite(PIN_DISPLAY_LED_WARNING, LOW); + digitalWrite(PIN_DISPLAY_LED_ERROR, HIGH); +} diff --git a/platforms/kia_soul/firmware/can_gateway/src/init.cpp b/platforms/kia_soul/firmware/can_gateway/src/init.cpp index b2a9cb93..acd726ed 100644 --- a/platforms/kia_soul/firmware/can_gateway/src/init.cpp +++ b/platforms/kia_soul/firmware/can_gateway/src/init.cpp @@ -12,6 +12,7 @@ #include "globals.h" #include "init.h" +#include "display.h" void init_globals( void ) @@ -62,6 +63,6 @@ void init_communication_interfaces( void ) DEBUG_PRINT( "init Control CAN - "); init_can( g_control_can ); - DEBUG_PRINT( "init display"); - g_display.begin(); + DEBUG_PRINTLN( "init display"); + init_display( ); } From 3d56bfb140208c04d8cd34e076751f715345068c Mon Sep 17 00:00:00 2001 From: Austin Morlan Date: Thu, 17 Aug 2017 10:11:50 -0700 Subject: [PATCH 13/84] Move display libs to firmware directory --- .../kia_soul/firmware => firmware}/can_gateway/include/display.h | 0 .../kia_soul/firmware => firmware}/can_gateway/src/display.cpp | 0 {platforms => firmware}/common/libs/gfx/gfx.cpp | 0 {platforms => firmware}/common/libs/gfx/gfx.h | 0 {platforms => firmware}/common/libs/gfx/glcdfont.c | 0 {platforms => firmware}/common/libs/gfx/license.txt | 0 {platforms => firmware}/common/libs/ssd1325/license.txt | 0 {platforms => firmware}/common/libs/ssd1325/ssd1325.cpp | 0 {platforms => firmware}/common/libs/ssd1325/ssd1325.h | 0 9 files changed, 0 insertions(+), 0 deletions(-) rename {platforms/kia_soul/firmware => firmware}/can_gateway/include/display.h (100%) rename {platforms/kia_soul/firmware => firmware}/can_gateway/src/display.cpp (100%) rename {platforms => firmware}/common/libs/gfx/gfx.cpp (100%) rename {platforms => firmware}/common/libs/gfx/gfx.h (100%) rename {platforms => firmware}/common/libs/gfx/glcdfont.c (100%) rename {platforms => firmware}/common/libs/gfx/license.txt (100%) rename {platforms => firmware}/common/libs/ssd1325/license.txt (100%) rename {platforms => firmware}/common/libs/ssd1325/ssd1325.cpp (100%) rename {platforms => firmware}/common/libs/ssd1325/ssd1325.h (100%) diff --git a/platforms/kia_soul/firmware/can_gateway/include/display.h b/firmware/can_gateway/include/display.h similarity index 100% rename from platforms/kia_soul/firmware/can_gateway/include/display.h rename to firmware/can_gateway/include/display.h diff --git a/platforms/kia_soul/firmware/can_gateway/src/display.cpp b/firmware/can_gateway/src/display.cpp similarity index 100% rename from platforms/kia_soul/firmware/can_gateway/src/display.cpp rename to firmware/can_gateway/src/display.cpp diff --git a/platforms/common/libs/gfx/gfx.cpp b/firmware/common/libs/gfx/gfx.cpp similarity index 100% rename from platforms/common/libs/gfx/gfx.cpp rename to firmware/common/libs/gfx/gfx.cpp diff --git a/platforms/common/libs/gfx/gfx.h b/firmware/common/libs/gfx/gfx.h similarity index 100% rename from platforms/common/libs/gfx/gfx.h rename to firmware/common/libs/gfx/gfx.h diff --git a/platforms/common/libs/gfx/glcdfont.c b/firmware/common/libs/gfx/glcdfont.c similarity index 100% rename from platforms/common/libs/gfx/glcdfont.c rename to firmware/common/libs/gfx/glcdfont.c diff --git a/platforms/common/libs/gfx/license.txt b/firmware/common/libs/gfx/license.txt similarity index 100% rename from platforms/common/libs/gfx/license.txt rename to firmware/common/libs/gfx/license.txt diff --git a/platforms/common/libs/ssd1325/license.txt b/firmware/common/libs/ssd1325/license.txt similarity index 100% rename from platforms/common/libs/ssd1325/license.txt rename to firmware/common/libs/ssd1325/license.txt diff --git a/platforms/common/libs/ssd1325/ssd1325.cpp b/firmware/common/libs/ssd1325/ssd1325.cpp similarity index 100% rename from platforms/common/libs/ssd1325/ssd1325.cpp rename to firmware/common/libs/ssd1325/ssd1325.cpp diff --git a/platforms/common/libs/ssd1325/ssd1325.h b/firmware/common/libs/ssd1325/ssd1325.h similarity index 100% rename from platforms/common/libs/ssd1325/ssd1325.h rename to firmware/common/libs/ssd1325/ssd1325.h From 3f893007b0756e27f17a90fa0902ca31380b50d2 Mon Sep 17 00:00:00 2001 From: Austin Morlan Date: Thu, 17 Aug 2017 11:59:55 -0700 Subject: [PATCH 14/84] Add empty display mock --- firmware/common/testing/mocks/ssd1325.h | 22 ++++++++++++++++++++++ 1 file changed, 22 insertions(+) create mode 100644 firmware/common/testing/mocks/ssd1325.h diff --git a/firmware/common/testing/mocks/ssd1325.h b/firmware/common/testing/mocks/ssd1325.h new file mode 100644 index 00000000..537dad4d --- /dev/null +++ b/firmware/common/testing/mocks/ssd1325.h @@ -0,0 +1,22 @@ +class SSD1325 { +public: + SSD1325(int8_t SID, int8_t SCLK, int8_t DC, int8_t RST, int8_t CS){} + + void begin(void); + void eraseBuffer(void); + void sendBuffer(void); + +private: + int8_t sid; + int8_t sclk; + int8_t dc; + int8_t rst; + int8_t cs; + + void startSendCommand(void); + void stopSendCommand(void); + void startSendData(void); + void stopSendData(void); + + void drawPixel(int16_t x, int16_t y, uint16_t color); +}; From e09b110891f26e297067dd7dc7b81d5242898fea Mon Sep 17 00:00:00 2001 From: Austin Morlan Date: Thu, 17 Aug 2017 12:01:26 -0700 Subject: [PATCH 15/84] Use enums for module DTCs Prior to this commit the DTCs were macros, but the gateway display needs to know how many DTCs each module has which requires another macro that needs to be updated every time a new DTC is added. This commit changes the macro to an enum instead so that the last item in the enum is always the number of DTCs in that enum. --- api/include/can_protocols/brake_can_protocol.h | 11 +++++++++-- api/include/can_protocols/steering_can_protocol.h | 11 +++++++++-- api/include/can_protocols/throttle_can_protocol.h | 12 +++++++++--- 3 files changed, 27 insertions(+), 7 deletions(-) diff --git a/api/include/can_protocols/brake_can_protocol.h b/api/include/can_protocols/brake_can_protocol.h index 33f5d10c..35b2fc6c 100644 --- a/api/include/can_protocols/brake_can_protocol.h +++ b/api/include/can_protocols/brake_can_protocol.h @@ -38,10 +38,17 @@ #define OSCC_BRAKE_REPORT_PUBLISH_FREQ_IN_HZ (50) /* - * @brief Brake DTC bitfield position indicating an invalid sensor value. + * @brief Enumeration of all possible brake DTCs. * */ -#define OSCC_BRAKE_DTC_INVALID_SENSOR_VAL (0x0) +enum +{ + /* DTC bitfield position indicating an invalid sensor value. */ + OSCC_BRAKE_DTC_INVALID_SENSOR_VAL = 0, + + /* Number of possible brake DTCs. */ + OSCC_BRAKE_DTC_COUNT +}; #pragma pack(push) diff --git a/api/include/can_protocols/steering_can_protocol.h b/api/include/can_protocols/steering_can_protocol.h index 29a578bf..bb4845ae 100644 --- a/api/include/can_protocols/steering_can_protocol.h +++ b/api/include/can_protocols/steering_can_protocol.h @@ -38,10 +38,17 @@ #define OSCC_REPORT_STEERING_PUBLISH_FREQ_IN_HZ (50) /* - * @brief Steering DTC bitfield position indicating an invalid sensor value. + * @brief Enumeration of all possible steering DTCs. * */ -#define OSCC_STEERING_DTC_INVALID_SENSOR_VAL (0x0) +enum +{ + /* DTC bitfield position indicating an invalid sensor value. */ + OSCC_STEERING_DTC_INVALID_SENSOR_VAL = 0, + + /* Number of possible steering DTCs. */ + OSCC_STEERING_DTC_COUNT +}; #pragma pack(push) diff --git a/api/include/can_protocols/throttle_can_protocol.h b/api/include/can_protocols/throttle_can_protocol.h index 64ea0192..9c65446c 100644 --- a/api/include/can_protocols/throttle_can_protocol.h +++ b/api/include/can_protocols/throttle_can_protocol.h @@ -40,12 +40,18 @@ */ #define OSCC_REPORT_THROTTLE_PUBLISH_FREQ_IN_HZ (50) - /* - * @brief Throttle DTC bitfield position indicating an invalid sensor value. + * @brief Enumeration of all possible throttle DTCs. * */ -#define OSCC_THROTTLE_DTC_INVALID_SENSOR_VAL (0x0) +enum +{ + /* DTC bitfield position indicating an invalid sensor value. */ + OSCC_THROTTLE_DTC_INVALID_SENSOR_VAL = 0, + + /* Number of possible throttle DTCs. */ + OSCC_THROTTLE_DTC_COUNT +}; #pragma pack(push) From d4a4decd8f9318033fb4aa090ae75d20fb6243be Mon Sep 17 00:00:00 2001 From: Austin Morlan Date: Thu, 17 Aug 2017 12:05:13 -0700 Subject: [PATCH 16/84] Add initializaton of display --- firmware/can_gateway/include/globals.h | 4 ++++ firmware/can_gateway/include/init.h | 13 +++++++++++++ firmware/can_gateway/src/init.cpp | 12 ++++++++++++ 3 files changed, 29 insertions(+) diff --git a/firmware/can_gateway/include/globals.h b/firmware/can_gateway/include/globals.h index c16f27e8..27717d82 100644 --- a/firmware/can_gateway/include/globals.h +++ b/firmware/can_gateway/include/globals.h @@ -97,4 +97,8 @@ #endif +EXTERN kia_soul_gateway_display_state_s g_display_state; + + + #endif /* _OSCC_KIA_SOUL_CAN_GATEWAY_GLOBALS_H_ */ diff --git a/firmware/can_gateway/include/init.h b/firmware/can_gateway/include/init.h index 82686bcd..9455a41a 100644 --- a/firmware/can_gateway/include/init.h +++ b/firmware/can_gateway/include/init.h @@ -9,6 +9,19 @@ #define _OSCC_KIA_SOUL_CAN_GATEWAY_INIT_H_ +// **************************************************************************** +// Function: init_globals +// +// Purpose: Initialize values of global variables. +// +// Returns: void +// +// Parameters: void +// +// **************************************************************************** +void init_globals( void ); + + // **************************************************************************** // Function: init_communication_interfaces // diff --git a/firmware/can_gateway/src/init.cpp b/firmware/can_gateway/src/init.cpp index d7374b5d..5df611cb 100644 --- a/firmware/can_gateway/src/init.cpp +++ b/firmware/can_gateway/src/init.cpp @@ -12,6 +12,15 @@ #include "init.h" +void init_globals( void ) +{ + memset( + &g_display_state, + 0, + sizeof(g_display_state) ); +} + + void init_communication_interfaces( void ) { #ifdef DEBUG @@ -23,4 +32,7 @@ void init_communication_interfaces( void ) DEBUG_PRINT( "init Control CAN - "); init_can( g_control_can ); + + DEBUG_PRINTLN( "init display"); + init_display( ); } From 74c2f0d2234beadd493b3660bdcf74a3b24d5020 Mon Sep 17 00:00:00 2001 From: Austin Morlan Date: Thu, 17 Aug 2017 12:12:00 -0700 Subject: [PATCH 17/84] Remove gateway status and DTC from display Prior to this commit, the display had gateway status on the status screen and displayed gateway DTCs on the DTC screen, which is no longer applicable following the recent code reorganization and rewrite which reduces the responsibilities of the gateway to simple OBD message forwarding. This commit removes all gateway display items. --- firmware/can_gateway/include/display.h | 21 +------ firmware/can_gateway/src/display.cpp | 80 +++----------------------- 2 files changed, 11 insertions(+), 90 deletions(-) diff --git a/firmware/can_gateway/include/display.h b/firmware/can_gateway/include/display.h index 06b1158f..b4b8670a 100644 --- a/firmware/can_gateway/include/display.h +++ b/firmware/can_gateway/include/display.h @@ -9,9 +9,9 @@ #define _OSCC_KIA_SOUL_CAN_GATEWAY_DISPLAY_H_ -#include "brake_can_protocol.h" -#include "steering_can_protocol.h" -#include "throttle_can_protocol.h" +#include "can_protocols/brake_can_protocol.h" +#include "can_protocols/steering_can_protocol.h" +#include "can_protocols/throttle_can_protocol.h" /** @@ -26,19 +26,6 @@ typedef enum } screen_t; -/** - * @brief Enumeration of possible gateway statuses. - * - */ -typedef enum -{ - GATEWAY_STATUS_UNKNOWN, - GATEWAY_STATUS_GOOD, - GATEWAY_STATUS_WARNING, - GATEWAY_STATUS_ERROR -} gateway_status_t; - - /** * @brief Enumeration of possible module statuses. * @@ -58,7 +45,6 @@ typedef enum */ typedef struct { - gateway_status_t gateway; module_status_t brakes; module_status_t steering; module_status_t throttle; @@ -71,7 +57,6 @@ typedef struct */ typedef struct { - bool gateway[OSCC_GATEWAY_DTC_COUNT]; bool brake[OSCC_BRAKE_DTC_COUNT]; bool steering[OSCC_STEERING_DTC_COUNT]; bool throttle[OSCC_THROTTLE_DTC_COUNT]; diff --git a/firmware/can_gateway/src/display.cpp b/firmware/can_gateway/src/display.cpp index 1ad1827f..ff5bee62 100644 --- a/firmware/can_gateway/src/display.cpp +++ b/firmware/can_gateway/src/display.cpp @@ -5,9 +5,9 @@ #include "globals.h" #include "debug.h" -#include "brake_can_protocol.h" -#include "steering_can_protocol.h" -#include "throttle_can_protocol.h" +#include "can_protocols/brake_can_protocol.h" +#include "can_protocols/steering_can_protocol.h" +#include "can_protocols/throttle_can_protocol.h" #include "oscc_time.h" #include "display.h" @@ -25,29 +25,23 @@ */ #define ORIGIN_Y_POS ( 0 ) -/* - * @brief X pixel position of the DTC screen's gateway column. - * - */ -#define GATEWAY_DTC_X_POS ( 0 ) - /* * @brief X pixel position of the DTC screen's brake column. * */ -#define BRAKE_DTC_X_POS ( 33 ) +#define BRAKE_DTC_X_POS ( 0 ) /* * @brief X pixel position of the DTC screen's steering column. * */ -#define STEERING_DTC_X_POS ( 66 ) +#define STEERING_DTC_X_POS ( 33 ) /* * @brief X pixel position of the DTC screen's throttle column. * */ -#define THROTTLE_DTC_X_POS ( 99 ) +#define THROTTLE_DTC_X_POS ( 66 ) /* * @brief Pixel height of a character on the display. @@ -62,14 +56,6 @@ #define DISPLAY_UPDATE_INTERVAL_IN_MS ( 250 ) -static const char * gateway_status_strings[] = -{ - "UNKNOWN", - "GOOD", - "WARNING", - "ERROR" -}; - static const char * module_status_strings[] = { "UNKNOWN", @@ -82,9 +68,7 @@ static const char * module_status_strings[] = static void display_status_screen( void ); static void display_dtc_screen( void ); static void update_leds( ); -static void print_gateway_status( gateway_status_t status ); static void print_module_status( module_status_t status ); -static void print_gateway_dtcs( void ); static void print_brake_dtcs( void ); static void print_steering_dtcs( void ); static void print_throttle_dtcs( void ); @@ -148,15 +132,13 @@ void update_display( void ) static void update_leds( void ) { - if( (g_display_state.status_screen.gateway == GATEWAY_STATUS_ERROR) - || (g_display_state.status_screen.brakes == MODULE_STATUS_ERROR) + if( (g_display_state.status_screen.brakes == MODULE_STATUS_ERROR) || (g_display_state.status_screen.steering == MODULE_STATUS_ERROR) || (g_display_state.status_screen.throttle == MODULE_STATUS_ERROR) ) { enable_error_led( ); } - else if( (g_display_state.status_screen.gateway == GATEWAY_STATUS_WARNING) - || (g_display_state.status_screen.brakes == MODULE_STATUS_UNKNOWN) + else if( (g_display_state.status_screen.brakes == MODULE_STATUS_UNKNOWN) || (g_display_state.status_screen.steering == MODULE_STATUS_UNKNOWN) || (g_display_state.status_screen.throttle == MODULE_STATUS_UNKNOWN) ) { @@ -173,9 +155,6 @@ static void display_status_screen( void ) { g_display.eraseBuffer(); - g_display.print( "Gateway: " ); - print_gateway_status( g_display_state.status_screen.gateway ); - g_display.print( "Brakes: " ); print_module_status( g_display_state.status_screen.brakes ); @@ -193,12 +172,6 @@ static void display_dtc_screen( void ) { g_display.eraseBuffer( ); - if( (g_display_state.status_screen.gateway == GATEWAY_STATUS_ERROR) - || (g_display_state.status_screen.gateway == GATEWAY_STATUS_WARNING) ) - { - print_gateway_dtcs( ); - } - if( g_display_state.status_screen.brakes == MODULE_STATUS_ERROR ) { print_brake_dtcs( ); @@ -218,25 +191,6 @@ static void display_dtc_screen( void ) } -static void print_gateway_status( gateway_status_t status ) -{ - const char * status_string = gateway_status_strings[status]; - - if( status == GATEWAY_STATUS_ERROR ) - { - g_display.setTextColor( BLACK, WHITE ); - g_display.print( status_string ); - g_display.setTextColor( WHITE, BLACK ); - } - else - { - g_display.print( status_string ); - } - - g_display.print( "\n\n") ; -} - - static void print_module_status( module_status_t status ) { const char * status_string = module_status_strings[status]; @@ -256,24 +210,6 @@ static void print_module_status( module_status_t status ) } -static void print_gateway_dtcs( void ) -{ - g_display.setCursor( GATEWAY_DTC_X_POS, ORIGIN_Y_POS ); - - for( int dtc = 0; dtc < OSCC_GATEWAY_DTC_COUNT; ++dtc ) - { - if( g_display_state.dtc_screen.gateway[dtc] == true ) - { - print_dtc( "P1G", dtc ); - } - - g_display.setCursor( - GATEWAY_DTC_X_POS, - (CHARACTER_HEIGHT + (dtc * CHARACTER_HEIGHT)) ); - } -} - - static void print_brake_dtcs( void ) { g_display.setCursor( BRAKE_DTC_X_POS, ORIGIN_Y_POS ); From 6441d691beea10a6a20b57817f2e456d4f881f68 Mon Sep 17 00:00:00 2001 From: Austin Morlan Date: Thu, 17 Aug 2017 12:40:53 -0700 Subject: [PATCH 18/84] Replace display timeout checking with timer --- firmware/can_gateway/CMakeLists.txt | 5 ++- firmware/can_gateway/include/display.h | 7 +++ firmware/can_gateway/include/timer.h | 25 +++++++++++ firmware/can_gateway/src/communications.cpp | 2 + firmware/can_gateway/src/display.cpp | 47 +++++++-------------- firmware/can_gateway/src/main.cpp | 3 ++ firmware/can_gateway/src/timer.cpp | 16 +++++++ 7 files changed, 72 insertions(+), 33 deletions(-) create mode 100644 firmware/can_gateway/include/timer.h create mode 100644 firmware/can_gateway/src/timer.cpp diff --git a/firmware/can_gateway/CMakeLists.txt b/firmware/can_gateway/CMakeLists.txt index 9822cf3c..8177a36a 100644 --- a/firmware/can_gateway/CMakeLists.txt +++ b/firmware/can_gateway/CMakeLists.txt @@ -21,13 +21,15 @@ generate_arduino_firmware( ${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/timer/oscc_timer.cpp ${CMAKE_SOURCE_DIR}/common/libs/ssd1325/ssd1325.cpp ${CMAKE_SOURCE_DIR}/common/libs/gfx/gfx.cpp src/main.cpp src/globals.cpp src/init.cpp src/communications.cpp - src/display.cpp) + src/display.cpp + src/timer.cpp) target_include_directories( can-gateway @@ -38,6 +40,7 @@ target_include_directories( ${CMAKE_SOURCE_DIR}/common/libs/mcp_can ${CMAKE_SOURCE_DIR}/common/libs/serial ${CMAKE_SOURCE_DIR}/common/libs/can + ${CMAKE_SOURCE_DIR}/common/libs/timer ${CMAKE_SOURCE_DIR}/common/libs/ssd1325 ${CMAKE_SOURCE_DIR}/common/libs/gfx ${CMAKE_SOURCE_DIR}/../api/include) diff --git a/firmware/can_gateway/include/display.h b/firmware/can_gateway/include/display.h index b4b8670a..12f6adf8 100644 --- a/firmware/can_gateway/include/display.h +++ b/firmware/can_gateway/include/display.h @@ -14,6 +14,13 @@ #include "can_protocols/throttle_can_protocol.h" +/* +* @brief Frequency of updates of display content. [Hz] +* +*/ +#define DISPLAY_UPDATE_FREQUENCY_IN_HZ ( 4 ) + + /** * @brief Enumeration of possible screens. * diff --git a/firmware/can_gateway/include/timer.h b/firmware/can_gateway/include/timer.h new file mode 100644 index 00000000..46d78be8 --- /dev/null +++ b/firmware/can_gateway/include/timer.h @@ -0,0 +1,25 @@ +/** + * @file timer.h + * @brief Timer functionality. + * + */ + + +#ifndef _OSCC_CAN_GATEWAY_TIMER_H_ +#define _OSCC_CAN_GATEWAY_TIMER_H_ + + +// **************************************************************************** +// Function: start_timer +// +// Purpose: Start timer for updating the display. +// +// Returns: void +// +// Parameters: void +// +// **************************************************************************** +void start_timer( void ); + + +#endif /* _OSCC_CAN_GATEWAY_TIMER_H_ */ diff --git a/firmware/can_gateway/src/communications.cpp b/firmware/can_gateway/src/communications.cpp index d1938028..d83f06a6 100644 --- a/firmware/can_gateway/src/communications.cpp +++ b/firmware/can_gateway/src/communications.cpp @@ -23,11 +23,13 @@ void republish_obd_frames_to_control_can_bus( void ) || (rx_frame.id == KIA_SOUL_OBD_WHEEL_SPEED_CAN_ID) || (rx_frame.id == KIA_SOUL_OBD_BRAKE_PRESSURE_CAN_ID) ) { + cli(); g_control_can.sendMsgBuf( rx_frame.id, CAN_STANDARD, sizeof(rx_frame), (uint8_t *) &rx_frame.data ); + sei(); } } } diff --git a/firmware/can_gateway/src/display.cpp b/firmware/can_gateway/src/display.cpp index ff5bee62..5d038245 100644 --- a/firmware/can_gateway/src/display.cpp +++ b/firmware/can_gateway/src/display.cpp @@ -8,7 +8,6 @@ #include "can_protocols/brake_can_protocol.h" #include "can_protocols/steering_can_protocol.h" #include "can_protocols/throttle_can_protocol.h" -#include "oscc_time.h" #include "display.h" @@ -49,12 +48,6 @@ */ #define CHARACTER_HEIGHT ( 10 ) -/* - * @brief Amount of time between updates of display content. [milliseconds] - * - */ -#define DISPLAY_UPDATE_INTERVAL_IN_MS ( 250 ) - static const char * module_status_strings[] = { @@ -82,6 +75,7 @@ static void enable_error_led( void ); void init_display( void ) { + cli(); digitalWrite(PIN_DISPLAY_LED_GOOD, LOW); digitalWrite(PIN_DISPLAY_LED_WARNING, LOW); digitalWrite(PIN_DISPLAY_LED_ERROR, LOW); @@ -91,42 +85,31 @@ void init_display( void ) pinMode(PIN_DISPLAY_LED_ERROR, OUTPUT); g_display.begin(); + sei(); } void update_display( void ) { - update_leds( ); + cli(); + update_leds( ); - static unsigned long last_update_time = 0; - - bool timeout = false; - unsigned long current_time = GET_TIMESTAMP_MS(); + g_display.setCursor( ORIGIN_X_POS, ORIGIN_Y_POS ); + g_display.setTextColor( WHITE, BLACK ); - timeout = is_timeout( - last_update_time, - current_time, - DISPLAY_UPDATE_INTERVAL_IN_MS ); + read_button( ); - if ( timeout == true ) + if( g_display_state.current_screen == STATUS_SCREEN ) { - last_update_time = current_time; - - g_display.setCursor( ORIGIN_X_POS, ORIGIN_Y_POS ); - g_display.setTextColor( WHITE, BLACK ); - - read_button( ); - - if( g_display_state.current_screen == STATUS_SCREEN ) - { - display_status_screen( ); - } - else if( g_display_state.current_screen == DTC_SCREEN ) - { - display_dtc_screen( ); - } + display_status_screen( ); + } + else if( g_display_state.current_screen == DTC_SCREEN ) + { + display_dtc_screen( ); } + + sei(); } diff --git a/firmware/can_gateway/src/main.cpp b/firmware/can_gateway/src/main.cpp index 9bc8b7b4..f736420c 100644 --- a/firmware/can_gateway/src/main.cpp +++ b/firmware/can_gateway/src/main.cpp @@ -11,6 +11,7 @@ #include "globals.h" #include "communications.h" #include "init.h" +#include "timer.h" int main( void ) @@ -21,6 +22,8 @@ int main( void ) init_communication_interfaces( ); + start_timer( ); + wdt_enable( WDTO_250MS ); DEBUG_PRINTLN( "init complete" ); diff --git a/firmware/can_gateway/src/timer.cpp b/firmware/can_gateway/src/timer.cpp new file mode 100644 index 00000000..df004c6c --- /dev/null +++ b/firmware/can_gateway/src/timer.cpp @@ -0,0 +1,16 @@ +/** + * @file timer.cpp + * + */ + + +#include "oscc_timer.h" + +#include "timer.h" +#include "display.h" + + +void start_timer( void ) +{ + timer1_init( DISPLAY_UPDATE_FREQUENCY_IN_HZ, update_display ); +} From 654a49cfcc78cbd8fb7470ad213d6c543f032a22 Mon Sep 17 00:00:00 2001 From: Austin Morlan Date: Thu, 17 Aug 2017 16:07:35 -0700 Subject: [PATCH 19/84] Update display with new layout --- firmware/can_gateway/src/display.cpp | 141 ++++++++++++++++++++----- firmware/common/libs/ssd1325/ssd1325.h | 3 +- 2 files changed, 114 insertions(+), 30 deletions(-) diff --git a/firmware/can_gateway/src/display.cpp b/firmware/can_gateway/src/display.cpp index 5d038245..03788cb7 100644 --- a/firmware/can_gateway/src/display.cpp +++ b/firmware/can_gateway/src/display.cpp @@ -13,40 +13,84 @@ /* - * @brief Pixel position of the display's X origin. + * @brief X pixel position of where display drawing begins. * */ -#define ORIGIN_X_POS ( 0 ) +#define ORIGIN_X ( 4 ) /* - * @brief Pixel position of the display's Y origin. + * @brief Y pixel position of where display drawing begins. * */ -#define ORIGIN_Y_POS ( 0 ) +#define ORIGIN_Y ( 4 ) + +/* + * @brief Y pixel position of where the horizontal header line is drawn. + * + */ +#define HEADER_LINE_Y ( 14 ) + +/* + * @brief X pixel position of where the horizontal header line starts being drawn. + * + */ +#define HEADER_LINE_X_START ( 4 ) + +/* + * @brief X pixel position of where the horizontal header line stops being drawn. + * + */ +#define HEADER_LINE_X_STOP ( 125 ) + +/* + * @brief Y pixel position of where the brake status line is drawn. + * + */ +#define BRAKE_STATUS_Y ( 18 ) + +/* + * @brief Y pixel position of where the steering status line is drawn. + * + */ +#define STEERING_STATUS_Y ( 30 ) + +/* + * @brief Y pixel position of where the throttle status line is drawn. + * + */ +#define THROTTLE_STATUS_Y ( 42 ) + +/* + * @brief Y pixel position of the the first row on the DTC screen. + * + */ +#define DTC_Y_START ( 18 ) /* * @brief X pixel position of the DTC screen's brake column. * */ -#define BRAKE_DTC_X_POS ( 0 ) +#define BRAKE_DTC_X ( 4 ) /* * @brief X pixel position of the DTC screen's steering column. * */ -#define STEERING_DTC_X_POS ( 33 ) +#define STEERING_DTC_X ( 46 ) /* * @brief X pixel position of the DTC screen's throttle column. * */ -#define THROTTLE_DTC_X_POS ( 66 ) +#define THROTTLE_DTC_X ( 88 ) + /* - * @brief Pixel height of a character on the display. + * @brief Number of pixels between top of character in one row and top of character + * in the next row. * */ -#define CHARACTER_HEIGHT ( 10 ) +#define ROW_SPACING ( 12 ) static const char * module_status_strings[] = @@ -60,6 +104,7 @@ static const char * module_status_strings[] = static void display_status_screen( void ); static void display_dtc_screen( void ); +static void draw_header_line( void ); static void update_leds( ); static void print_module_status( module_status_t status ); static void print_brake_dtcs( void ); @@ -95,7 +140,7 @@ void update_display( void ) update_leds( ); - g_display.setCursor( ORIGIN_X_POS, ORIGIN_Y_POS ); + g_display.setCursor( ORIGIN_X, ORIGIN_Y ); g_display.setTextColor( WHITE, BLACK ); read_button( ); @@ -138,13 +183,24 @@ static void display_status_screen( void ) { g_display.eraseBuffer(); - g_display.print( "Brakes: " ); + g_display.setCursor( ORIGIN_X, ORIGIN_Y ); + g_display.print( "STATUS" ); + + draw_header_line( ); + + g_display.setCursor( ORIGIN_X, BRAKE_STATUS_Y ); + + g_display.print( "BRAKES: " ); print_module_status( g_display_state.status_screen.brakes ); - g_display.print( "Steering: " ); + g_display.setCursor( ORIGIN_X, STEERING_STATUS_Y ); + + g_display.print( "STEERING: " ); print_module_status( g_display_state.status_screen.steering ); - g_display.print( "Throttle: " ); + g_display.setCursor( ORIGIN_X, THROTTLE_STATUS_Y ); + + g_display.print( "THROTTLE: " ); print_module_status( g_display_state.status_screen.throttle ); g_display.sendBuffer(); @@ -155,6 +211,11 @@ static void display_dtc_screen( void ) { g_display.eraseBuffer( ); + g_display.setCursor( ORIGIN_X, ORIGIN_Y ); + g_display.print( "DTCS" ); + + draw_header_line( ); + if( g_display_state.status_screen.brakes == MODULE_STATUS_ERROR ) { print_brake_dtcs( ); @@ -174,6 +235,18 @@ static void display_dtc_screen( void ) } +static void draw_header_line( void ) +{ + g_display.setCursor( ORIGIN_X, HEADER_LINE_Y ); + + int pixel; + for( pixel = HEADER_LINE_X_START; pixel <= HEADER_LINE_X_STOP; ++pixel ) + { + g_display.drawPixel(pixel, HEADER_LINE_Y, WHITE); + } +} + + static void print_module_status( module_status_t status ) { const char * status_string = module_status_strings[status]; @@ -195,54 +268,66 @@ static void print_module_status( module_status_t status ) static void print_brake_dtcs( void ) { - g_display.setCursor( BRAKE_DTC_X_POS, ORIGIN_Y_POS ); + g_display.setCursor( BRAKE_DTC_X, DTC_Y_START ); + + int row_position = DTC_Y_START; for( int dtc = 0; dtc < OSCC_BRAKE_DTC_COUNT; ++dtc ) { if( g_display_state.dtc_screen.brake[dtc] == true ) { + g_display.setCursor( + BRAKE_DTC_X, + row_position ); + print_dtc( "P1B", dtc ); - } - g_display.setCursor( - BRAKE_DTC_X_POS, - (CHARACTER_HEIGHT + (dtc * CHARACTER_HEIGHT)) ); + row_position += ROW_SPACING; + } } } static void print_steering_dtcs( void ) { - g_display.setCursor( STEERING_DTC_X_POS, ORIGIN_Y_POS ) ; + g_display.setCursor( STEERING_DTC_X, DTC_Y_START ) ; + + int row_position = DTC_Y_START; for( int dtc = 0; dtc < OSCC_STEERING_DTC_COUNT; ++dtc ) { if( g_display_state.dtc_screen.steering[dtc] == true ) { + g_display.setCursor( + STEERING_DTC_X, + row_position ); + print_dtc( "P1S", dtc ); - } - g_display.setCursor( - STEERING_DTC_X_POS, - (CHARACTER_HEIGHT + (dtc * CHARACTER_HEIGHT)) ); + row_position += ROW_SPACING; + } } } static void print_throttle_dtcs( void ) { - g_display.setCursor( THROTTLE_DTC_X_POS, ORIGIN_Y_POS ); + g_display.setCursor( THROTTLE_DTC_X, DTC_Y_START ); + + int row_position = DTC_Y_START; for( int dtc = 0; dtc < OSCC_THROTTLE_DTC_COUNT; ++dtc ) { if( g_display_state.dtc_screen.throttle[dtc] == true ) { + g_display.setCursor( + THROTTLE_DTC_X, + row_position ); + print_dtc( "P1T", dtc ); - } - g_display.setCursor( - THROTTLE_DTC_X_POS, - (CHARACTER_HEIGHT + (dtc * CHARACTER_HEIGHT)) ); + row_position += ROW_SPACING; + } } } diff --git a/firmware/common/libs/ssd1325/ssd1325.h b/firmware/common/libs/ssd1325/ssd1325.h index 630b6d46..994d3b57 100644 --- a/firmware/common/libs/ssd1325/ssd1325.h +++ b/firmware/common/libs/ssd1325/ssd1325.h @@ -77,6 +77,7 @@ class SSD1325 : public GFX { void begin(void); void eraseBuffer(void); void sendBuffer(void); + void drawPixel(int16_t x, int16_t y, uint16_t color); private: int8_t sid; @@ -89,6 +90,4 @@ class SSD1325 : public GFX { void stopSendCommand(void); void startSendData(void); void stopSendData(void); - - void drawPixel(int16_t x, int16_t y, uint16_t color); }; From 13453ff98fec2fcc489ef052f8f320a6eacab91a Mon Sep 17 00:00:00 2001 From: Austin Morlan Date: Thu, 17 Aug 2017 16:21:38 -0700 Subject: [PATCH 20/84] Add Arduino.h include to display test mock --- firmware/common/testing/mocks/ssd1325.h | 2 ++ 1 file changed, 2 insertions(+) diff --git a/firmware/common/testing/mocks/ssd1325.h b/firmware/common/testing/mocks/ssd1325.h index 537dad4d..d5a0a599 100644 --- a/firmware/common/testing/mocks/ssd1325.h +++ b/firmware/common/testing/mocks/ssd1325.h @@ -1,3 +1,5 @@ +#include + class SSD1325 { public: SSD1325(int8_t SID, int8_t SCLK, int8_t DC, int8_t RST, int8_t CS){} From 2352c7248851eab63396fc35ad9f3c7cc9a60c67 Mon Sep 17 00:00:00 2001 From: Austin Morlan Date: Thu, 17 Aug 2017 16:26:01 -0700 Subject: [PATCH 21/84] Erase display buffer and write empty in init Prior to this commit, the display buffer was not being "erased" (i.e., initialized to 0s) at startup, which caused the display to show strange artifacts on boot. This commit erases the buffer and writes that empty buffer to the screen during init to ensure a fresh buffer. --- firmware/can_gateway/src/display.cpp | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/firmware/can_gateway/src/display.cpp b/firmware/can_gateway/src/display.cpp index 03788cb7..41345e3f 100644 --- a/firmware/can_gateway/src/display.cpp +++ b/firmware/can_gateway/src/display.cpp @@ -130,6 +130,10 @@ void init_display( void ) pinMode(PIN_DISPLAY_LED_ERROR, OUTPUT); g_display.begin(); + + g_display.eraseBuffer(); + g_display.sendBuffer(); + sei(); } From 7cbbcbe104a788afc1f6afe54f7ceac70d6950e6 Mon Sep 17 00:00:00 2001 From: Austin Morlan Date: Thu, 17 Aug 2017 17:01:02 -0700 Subject: [PATCH 22/84] Add module report parsing for display --- firmware/can_gateway/include/communications.h | 13 +++ firmware/can_gateway/include/display.h | 2 +- firmware/can_gateway/src/communications.cpp | 104 ++++++++++++++++++ firmware/can_gateway/src/display.cpp | 2 +- 4 files changed, 119 insertions(+), 2 deletions(-) diff --git a/firmware/can_gateway/include/communications.h b/firmware/can_gateway/include/communications.h index af8a4758..add042b2 100644 --- a/firmware/can_gateway/include/communications.h +++ b/firmware/can_gateway/include/communications.h @@ -12,6 +12,19 @@ #include "globals.h" +// **************************************************************************** +// Function: check_for_module_reports +// +// Purpose: Checks Control CAN bus for reports from the modules. +// +// Returns: void +// +// Parameters: void +// +// **************************************************************************** +void check_for_module_reports( void ); + + // **************************************************************************** // Function: republish_obd_frames_to_control_can_bus // diff --git a/firmware/can_gateway/include/display.h b/firmware/can_gateway/include/display.h index 12f6adf8..078f6709 100644 --- a/firmware/can_gateway/include/display.h +++ b/firmware/can_gateway/include/display.h @@ -64,7 +64,7 @@ typedef struct */ typedef struct { - bool brake[OSCC_BRAKE_DTC_COUNT]; + bool brakes[OSCC_BRAKE_DTC_COUNT]; bool steering[OSCC_STEERING_DTC_COUNT]; bool throttle[OSCC_THROTTLE_DTC_COUNT]; } dtc_screen_s; diff --git a/firmware/can_gateway/src/communications.cpp b/firmware/can_gateway/src/communications.cpp index d83f06a6..d37630a4 100644 --- a/firmware/can_gateway/src/communications.cpp +++ b/firmware/can_gateway/src/communications.cpp @@ -4,6 +4,7 @@ */ +#include "dtc.h" #include "mcp_can.h" #include "oscc_can.h" #include "vehicles.h" @@ -12,6 +13,34 @@ #include "communications.h" +static void parse_brake_report( uint8_t *data ); +static void parse_steering_report( uint8_t *data ); +static void parse_throttle_report( uint8_t *data ); + + +void check_for_module_reports( 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 ) + { + if ( rx_frame.id == OSCC_BRAKE_REPORT_CAN_ID ) + { + parse_brake_report( rx_frame.data ); + } + else if ( rx_frame.id == OSCC_STEERING_REPORT_CAN_ID ) + { + parse_steering_report( rx_frame.data ); + } + else if ( rx_frame.id == OSCC_THROTTLE_REPORT_CAN_ID ) + { + parse_throttle_report( rx_frame.data ); + } + } +} + + void republish_obd_frames_to_control_can_bus( void ) { can_frame_s rx_frame; @@ -33,3 +62,78 @@ void republish_obd_frames_to_control_can_bus( void ) } } } + + +static void parse_brake_report( uint8_t *data ) +{ + oscc_brake_report_s *report = (oscc_brake_report_s *) data; + + if ( report->enabled == 1 ) + { + g_display_state.status_screen.brakes = MODULE_STATUS_ENABLED; + } + else + { + g_display_state.status_screen.brakes = MODULE_STATUS_DISABLED; + } + + if( report->dtcs != 0 ) + { + g_display_state.status_screen.brakes = MODULE_STATUS_ERROR; + + if ( DTC_CHECK( report->dtcs, OSCC_BRAKE_DTC_INVALID_SENSOR_VAL ) != 0) + { + g_display_state.dtc_screen.brakes[OSCC_BRAKE_DTC_INVALID_SENSOR_VAL] = true; + } + } +} + + +static void parse_steering_report( uint8_t *data ) +{ + oscc_steering_report_s *report = (oscc_steering_report_s *) data; + + if ( report->enabled == 1 ) + { + g_display_state.status_screen.steering = MODULE_STATUS_ENABLED; + } + else + { + g_display_state.status_screen.steering = MODULE_STATUS_DISABLED; + } + + if( report->dtcs != 0 ) + { + g_display_state.status_screen.steering = MODULE_STATUS_ERROR; + + if ( DTC_CHECK( report->dtcs, OSCC_STEERING_DTC_INVALID_SENSOR_VAL ) != 0) + { + g_display_state.dtc_screen.steering[OSCC_STEERING_DTC_INVALID_SENSOR_VAL] = true; + } + } +} + + +static void parse_throttle_report( uint8_t *data ) +{ + oscc_throttle_report_s *report = (oscc_throttle_report_s *) data; + + if ( report->enabled == 1 ) + { + g_display_state.status_screen.throttle = MODULE_STATUS_ENABLED; + } + else + { + g_display_state.status_screen.throttle = MODULE_STATUS_DISABLED; + } + + if( report->dtcs != 0 ) + { + g_display_state.status_screen.throttle = MODULE_STATUS_ERROR; + + if ( DTC_CHECK( report->dtcs, OSCC_THROTTLE_DTC_INVALID_SENSOR_VAL ) != 0) + { + g_display_state.dtc_screen.throttle[OSCC_THROTTLE_DTC_INVALID_SENSOR_VAL] = true; + } + } +} diff --git a/firmware/can_gateway/src/display.cpp b/firmware/can_gateway/src/display.cpp index 41345e3f..13d22d65 100644 --- a/firmware/can_gateway/src/display.cpp +++ b/firmware/can_gateway/src/display.cpp @@ -278,7 +278,7 @@ static void print_brake_dtcs( void ) for( int dtc = 0; dtc < OSCC_BRAKE_DTC_COUNT; ++dtc ) { - if( g_display_state.dtc_screen.brake[dtc] == true ) + if( g_display_state.dtc_screen.brakes[dtc] == true ) { g_display.setCursor( BRAKE_DTC_X, From 0454dd2aa1e29e60e56c56ce193a0ed08869645f Mon Sep 17 00:00:00 2001 From: Austin Morlan Date: Wed, 18 Oct 2017 14:47:51 -0700 Subject: [PATCH 23/84] Modify display library for use with display module --- firmware/can_gateway/include/globals.h | 52 +------ firmware/can_gateway/src/display.cpp | 44 +----- firmware/common/libs/ssd1325/ssd1325.cpp | 176 ++++++++++++++++++----- firmware/common/libs/ssd1325/ssd1325.h | 45 +++--- 4 files changed, 171 insertions(+), 146 deletions(-) diff --git a/firmware/can_gateway/include/globals.h b/firmware/can_gateway/include/globals.h index 27717d82..3f61436f 100644 --- a/firmware/can_gateway/include/globals.h +++ b/firmware/can_gateway/include/globals.h @@ -27,65 +27,17 @@ */ #define PIN_CONTROL_CAN_CHIP_SELECT ( 10 ) -/* - * @brief SPI SCLK pin to display. - * - */ -#define PIN_DISPLAY_SCLK ( 13 ) - -/* - * @brief SPI MOSI pin to display. - * - */ -#define PIN_DISPLAY_MOSI ( 11 ) - /* * @brief SPI CS pin to display. * */ -#define PIN_DISPLAY_CS ( 7 ) - -/* - * @brief Reset pin to display. - * - */ -#define PIN_DISPLAY_RESET ( 6 ) - -/* - * @brief DC pin to display. - * - */ -#define PIN_DISPLAY_DC ( 5 ) - -/* - * @brief Pin of display button. - * - */ -#define PIN_DISPLAY_BUTTON ( 4 ) - -/* - * @brief Pin of good (green) display LED. - * - */ -#define PIN_DISPLAY_LED_GOOD ( 8 ) - -/* - * @brief Pin of warning (yellow) display LED. - * - */ -#define PIN_DISPLAY_LED_WARNING ( 3 ) - -/* - * @brief Pin of error (red) display LED. - * - */ -#define PIN_DISPLAY_LED_ERROR ( 2 ) +#define PIN_DISPLAY_CHIP_SELECT ( 8 ) #ifdef GLOBAL_DEFINED MCP_CAN g_obd_can( PIN_OBD_CAN_CHIP_SELECT ); MCP_CAN g_control_can( PIN_CONTROL_CAN_CHIP_SELECT ); - SSD1325 g_display( PIN_DISPLAY_MOSI, PIN_DISPLAY_SCLK, PIN_DISPLAY_DC, PIN_DISPLAY_RESET, PIN_DISPLAY_CS ); + SSD1325 g_display( PIN_DISPLAY_CHIP_SELECT ); #define EXTERN #else diff --git a/firmware/can_gateway/src/display.cpp b/firmware/can_gateway/src/display.cpp index 13d22d65..4beeea8c 100644 --- a/firmware/can_gateway/src/display.cpp +++ b/firmware/can_gateway/src/display.cpp @@ -113,21 +113,11 @@ static void print_throttle_dtcs( void ); static void print_dtc( const char *type, int num ); static void print_padded_number( const unsigned int number ); static void read_button( void ); -static void enable_good_led( void ); -static void enable_warning_led( void ); -static void enable_error_led( void ); void init_display( void ) { cli(); - digitalWrite(PIN_DISPLAY_LED_GOOD, LOW); - digitalWrite(PIN_DISPLAY_LED_WARNING, LOW); - digitalWrite(PIN_DISPLAY_LED_ERROR, LOW); - - pinMode(PIN_DISPLAY_LED_GOOD, OUTPUT); - pinMode(PIN_DISPLAY_LED_WARNING, OUTPUT); - pinMode(PIN_DISPLAY_LED_ERROR, OUTPUT); g_display.begin(); @@ -168,17 +158,17 @@ static void update_leds( void ) || (g_display_state.status_screen.steering == MODULE_STATUS_ERROR) || (g_display_state.status_screen.throttle == MODULE_STATUS_ERROR) ) { - enable_error_led( ); + g_display.enableRedLed( ); } else if( (g_display_state.status_screen.brakes == MODULE_STATUS_UNKNOWN) || (g_display_state.status_screen.steering == MODULE_STATUS_UNKNOWN) || (g_display_state.status_screen.throttle == MODULE_STATUS_UNKNOWN) ) { - enable_warning_led( ); + g_display.enableYellowLed( ); } else { - enable_good_led( ); + g_display.enableGreenLed( ); } } @@ -356,35 +346,11 @@ static void print_padded_number( const unsigned int number ) static void read_button( void ) { - int button_val = digitalRead( PIN_DISPLAY_BUTTON ); + bool button_val = g_display.readButton(); - if( button_val == 1 ) + if( button_val == true ) { g_display_state.current_screen = (screen_t)((g_display_state.current_screen + 1) % SCREEN_COUNT); } } - - -static void enable_good_led( void ) -{ - digitalWrite(PIN_DISPLAY_LED_GOOD, HIGH); - digitalWrite(PIN_DISPLAY_LED_WARNING, LOW); - digitalWrite(PIN_DISPLAY_LED_ERROR, LOW); -} - - -static void enable_warning_led( void ) -{ - digitalWrite(PIN_DISPLAY_LED_GOOD, LOW); - digitalWrite(PIN_DISPLAY_LED_WARNING, HIGH); - digitalWrite(PIN_DISPLAY_LED_ERROR, LOW); -} - - -static void enable_error_led( void ) -{ - digitalWrite(PIN_DISPLAY_LED_GOOD, LOW); - digitalWrite(PIN_DISPLAY_LED_WARNING, LOW); - digitalWrite(PIN_DISPLAY_LED_ERROR, HIGH); -} diff --git a/firmware/common/libs/ssd1325/ssd1325.cpp b/firmware/common/libs/ssd1325/ssd1325.cpp index 4c471d55..2a249dc6 100644 --- a/firmware/common/libs/ssd1325/ssd1325.cpp +++ b/firmware/common/libs/ssd1325/ssd1325.cpp @@ -22,6 +22,13 @@ All text above, and the splash screen below must be included in any redistributi #include "glcdfont.c" #include "ssd1325.h" + +// Chip select of first shift register +#define SHIFT_REGISTER_CHIP_SELECT_1 ( 4 ) + +// Chip select of second shift register +#define SHIFT_REGISTER_CHIP_SELECT_2 ( 5 ) + // a 5x7 font table extern const uint8_t PROGMEM font[]; @@ -100,19 +107,19 @@ void SSD1325::begin(void) SPI.setDataMode(SPI_MODE0); SPI.setClockDivider(SPI_CLOCK_DIV2); - pinMode(dc, OUTPUT); - pinMode(rst, OUTPUT); + pinMode(SHIFT_REGISTER_CHIP_SELECT_1, OUTPUT); + pinMode(SHIFT_REGISTER_CHIP_SELECT_2, OUTPUT); pinMode(cs, OUTPUT); - digitalWrite(rst, HIGH); - // VDD (3.3V) goes high at start, lets just chill for a ms + digitalWrite(SHIFT_REGISTER_CHIP_SELECT_1, LOW); + digitalWrite(SHIFT_REGISTER_CHIP_SELECT_2, HIGH); + digitalWrite(cs, HIGH); + + setRes(1); delay(1); - // bring reset low - digitalWrite(rst, LOW); - // wait 10ms + setRes(0); delay(10); - // bring out of reset - digitalWrite(rst, HIGH); + setRes(1); delay(500); @@ -206,31 +213,6 @@ void SSD1325::eraseBuffer(void) } -void SSD1325::startSendCommand(void) -{ - digitalWrite(dc, LOW); - digitalWrite(cs, LOW); -} - -void SSD1325::stopSendCommand(void) -{ - digitalWrite(cs, HIGH); - digitalWrite(dc, HIGH); -} - -void SSD1325::startSendData(void) -{ - digitalWrite(dc, HIGH); - digitalWrite(cs, LOW); -} - -void SSD1325::stopSendData(void) -{ - digitalWrite(cs, HIGH); - digitalWrite(dc, LOW); -} - - void SSD1325::drawPixel(int16_t x, int16_t y, uint16_t color) { if ((x >= width()) || (y >= height()) || (x < 0) || (y < 0)) @@ -242,7 +224,7 @@ void SSD1325::drawPixel(int16_t x, int16_t y, uint16_t color) switch (getRotation()) { case 1: - adagfx_swap(x, y); + gfx_swap(x, y); x = WIDTH - x - 1; break; case 2: @@ -250,7 +232,7 @@ void SSD1325::drawPixel(int16_t x, int16_t y, uint16_t color) y = HEIGHT - y - 1; break; case 3: - adagfx_swap(x, y); + gfx_swap(x, y); y = HEIGHT - y - 1; break; } @@ -265,3 +247,125 @@ void SSD1325::drawPixel(int16_t x, int16_t y, uint16_t color) buffer[x+ (y/8)*SSD1325_LCDWIDTH] &= ~_BV((y%8)); } } + + +bool SSD1325::readButton() +{ + digitalWrite(SHIFT_REGISTER_CHIP_SELECT_2, HIGH); + delay(1); + digitalWrite(SHIFT_REGISTER_CHIP_SELECT_2, LOW); + delay(1); + digitalWrite(SCK, LOW); + delay(1); + uint8_t data = SPI.transfer(0); + delay(1); + digitalWrite(SCK, HIGH); + delay(1); + digitalWrite(SHIFT_REGISTER_CHIP_SELECT_2, HIGH); + delay(1); + + if (data & 0x01) + { + return false; + } + else + { + return true; + } +} + + +void SSD1325::enableRedLed() +{ + shift_register_data = ((0x01 << 4) & 0x70) | (shift_register_data & ~0x70); + + digitalWrite(SHIFT_REGISTER_CHIP_SELECT_1, LOW); + delay(1); + SPI.transfer(shift_register_data); + delay(1); + digitalWrite(SHIFT_REGISTER_CHIP_SELECT_1, HIGH); + delay(1); + digitalWrite(SHIFT_REGISTER_CHIP_SELECT_1, LOW); +} + + +void SSD1325::enableYellowLed() +{ + shift_register_data = ((0x02 << 4) & 0x70) | (shift_register_data & ~0x70); + + digitalWrite(SHIFT_REGISTER_CHIP_SELECT_1, LOW); + delay(1); + SPI.transfer(shift_register_data); + delay(1); + digitalWrite(SHIFT_REGISTER_CHIP_SELECT_1, HIGH); + delay(1); + digitalWrite(SHIFT_REGISTER_CHIP_SELECT_1, LOW); +} + + +void SSD1325::enableGreenLed() +{ + shift_register_data = ((0x04 << 4) & 0x70) | (shift_register_data & ~0x70); + + digitalWrite(SHIFT_REGISTER_CHIP_SELECT_1, LOW); + delay(1); + SPI.transfer(shift_register_data); + delay(1); + digitalWrite(SHIFT_REGISTER_CHIP_SELECT_1, HIGH); + delay(1); + digitalWrite(SHIFT_REGISTER_CHIP_SELECT_1, LOW); +} + + +void SSD1325::setDC(uint8_t value){ + shift_register_data = ((value << 7) & 0x80) | (shift_register_data & ~0x80); + + digitalWrite(SHIFT_REGISTER_CHIP_SELECT_1, LOW); + delay(1); + SPI.transfer(shift_register_data); + delay(1); + digitalWrite(SHIFT_REGISTER_CHIP_SELECT_1, HIGH); + delay(1); + digitalWrite(SHIFT_REGISTER_CHIP_SELECT_1, LOW); +} + + +void SSD1325::setRes(uint8_t value){ + shift_register_data = ((value << 3) & 0x08) | (shift_register_data & ~0x08); + + digitalWrite(SHIFT_REGISTER_CHIP_SELECT_1, LOW); + delay(1); + SPI.transfer(shift_register_data); + delay(1); + digitalWrite(SHIFT_REGISTER_CHIP_SELECT_1, HIGH); + delay(1); + digitalWrite(SHIFT_REGISTER_CHIP_SELECT_1, LOW); +} + + +void SSD1325::startSendCommand(void) +{ + setDC(0); + digitalWrite(cs, LOW); +} + + +void SSD1325::stopSendCommand(void) +{ + digitalWrite(cs, HIGH); + setDC(1); +} + + +void SSD1325::startSendData(void) +{ + setDC(1); + digitalWrite(cs, LOW); +} + + +void SSD1325::stopSendData(void) +{ + digitalWrite(cs, HIGH); + setDC(0); +} diff --git a/firmware/common/libs/ssd1325/ssd1325.h b/firmware/common/libs/ssd1325/ssd1325.h index 994d3b57..8006dd0c 100644 --- a/firmware/common/libs/ssd1325/ssd1325.h +++ b/firmware/common/libs/ssd1325/ssd1325.h @@ -29,8 +29,8 @@ All text above, and the splash screen must be included in any redistribution #include "gfx.h" -#ifndef adagfx_swap -#define adagfx_swap(a, b) { uint8_t t = a; a = b; b = t; } +#ifndef gfx_swap +#define gfx_swap(a, b) { uint8_t t = a; a = b; b = t; } #endif #define BLACK 0 @@ -71,23 +71,26 @@ All text above, and the splash screen must be included in any redistribution #define SSD1325_COPY 0x25 class SSD1325 : public GFX { - public: - SSD1325(int8_t SID, int8_t SCLK, int8_t DC, int8_t RST, int8_t CS) : GFX(128,64), sid(SID), sclk(SCLK), dc(DC), rst(RST), cs(CS) {} - - void begin(void); - void eraseBuffer(void); - void sendBuffer(void); - void drawPixel(int16_t x, int16_t y, uint16_t color); - - private: - int8_t sid; - int8_t sclk; - int8_t dc; - int8_t rst; - int8_t cs; - - void startSendCommand(void); - void stopSendCommand(void); - void startSendData(void); - void stopSendData(void); + public: + SSD1325(int8_t CS) : GFX(128,64), cs(CS) {} + + void begin(void); + void eraseBuffer(void); + void sendBuffer(void); + void drawPixel(int16_t x, int16_t y, uint16_t color); + bool readButton(void); + void enableRedLed(void); + void enableYellowLed(void); + void enableGreenLed(void); + + private: + int8_t cs; + uint8_t shift_register_data; + + void setDC(uint8_t value); + void setRes(uint8_t value); + void startSendCommand(void); + void stopSendCommand(void); + void startSendData(void); + void stopSendData(void); }; From 499d92bfbc1a6bd27522ef7dd43391ea11875566 Mon Sep 17 00:00:00 2001 From: Austin Morlan Date: Wed, 18 Oct 2017 15:51:53 -0700 Subject: [PATCH 24/84] Add gateway board files --- hardware/boards/gateway/gateway_r0.brd | 15485 +++++++++++++++++++++++ hardware/boards/gateway/gateway_r0.sch | 8778 +++++++++++++ 2 files changed, 24263 insertions(+) create mode 100644 hardware/boards/gateway/gateway_r0.brd create mode 100644 hardware/boards/gateway/gateway_r0.sch diff --git a/hardware/boards/gateway/gateway_r0.brd b/hardware/boards/gateway/gateway_r0.brd new file mode 100644 index 00000000..7c25452c --- /dev/null +++ b/hardware/boards/gateway/gateway_r0.brd @@ -0,0 +1,15485 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +CANH +CANL + + + + + + + + + + + + + + + + + + + ++12V +GND +PWR +CAN-TX +CAN-RX +INT + + + + + + + + + + + + + + + + + + + + + + + + + + +CANL +CANH +Display +CAN-TX +CAN-RX +INT + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + + + + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + +Plastic- encapsulated transistors + + +<b>CRYSTAL</b> + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + +>name + + + + + + + + + + + + + +>NAME + + + + + + + + +>NAME + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +>NAME + + +<b>PLASTIC SMALL-OUTLINE PACKAGE SO 20</b> JEDEC MO-153, PW Type<p> +Source: www.ti.com/.. slvs087l.pdf + + + + + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +<b>Description:</b> Standard 0402 Package for Resistors<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. + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/hardware/boards/gateway/gateway_r0.sch b/hardware/boards/gateway/gateway_r0.sch new file mode 100644 index 00000000..3233c5aa --- /dev/null +++ b/hardware/boards/gateway/gateway_r0.sch @@ -0,0 +1,8778 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +>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 + + +<b>Dual In Line Package</b> + + + + + + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + +<b>Wide Small Outline package</b> 300 mil + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +>VALUE +>NAME + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +<b>Leadless Chip Carrier</b><p> Ceramic Package + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + +<b>PLASTIC SMALL-OUTLINE PACKAGE SO 20</b> JEDEC MO-153, PW Type<p> +Source: www.ti.com/.. slvs087l.pdf + + + + + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + + + + +>NAME + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + + +>NAME +>VALUE + + + + + + + + + + + +>NAME +GND +VCC + + + + + + + + +>NAME +>VALUE + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +Octal <b>BUFFER</b> and <b>LINE DRIVER</b>, 3-state + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +<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> + + + + + + + + + + + + + + + + +<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 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + From c9f7eae45c9cdc88535acc5e0d2e713bfb71fd06 Mon Sep 17 00:00:00 2001 From: Austin Morlan Date: Wed, 18 Oct 2017 16:05:52 -0700 Subject: [PATCH 25/84] Move GFX library to display library directory --- firmware/can_gateway/CMakeLists.txt | 4 ++-- firmware/common/libs/{ => ssd1325}/gfx/gfx.cpp | 0 firmware/common/libs/{ => ssd1325}/gfx/gfx.h | 0 firmware/common/libs/{ => ssd1325}/gfx/glcdfont.c | 0 firmware/common/libs/{ => ssd1325}/gfx/license.txt | 0 5 files changed, 2 insertions(+), 2 deletions(-) rename firmware/common/libs/{ => ssd1325}/gfx/gfx.cpp (100%) rename firmware/common/libs/{ => ssd1325}/gfx/gfx.h (100%) rename firmware/common/libs/{ => ssd1325}/gfx/glcdfont.c (100%) rename firmware/common/libs/{ => ssd1325}/gfx/license.txt (100%) diff --git a/firmware/can_gateway/CMakeLists.txt b/firmware/can_gateway/CMakeLists.txt index 8177a36a..b5a76658 100644 --- a/firmware/can_gateway/CMakeLists.txt +++ b/firmware/can_gateway/CMakeLists.txt @@ -23,7 +23,7 @@ generate_arduino_firmware( ${CMAKE_SOURCE_DIR}/common/libs/can/oscc_can.cpp ${CMAKE_SOURCE_DIR}/common/libs/timer/oscc_timer.cpp ${CMAKE_SOURCE_DIR}/common/libs/ssd1325/ssd1325.cpp - ${CMAKE_SOURCE_DIR}/common/libs/gfx/gfx.cpp + ${CMAKE_SOURCE_DIR}/common/libs/ssd1325/gfx/gfx.cpp src/main.cpp src/globals.cpp src/init.cpp @@ -42,5 +42,5 @@ target_include_directories( ${CMAKE_SOURCE_DIR}/common/libs/can ${CMAKE_SOURCE_DIR}/common/libs/timer ${CMAKE_SOURCE_DIR}/common/libs/ssd1325 - ${CMAKE_SOURCE_DIR}/common/libs/gfx + ${CMAKE_SOURCE_DIR}/common/libs/ssd1325/gfx ${CMAKE_SOURCE_DIR}/../api/include) diff --git a/firmware/common/libs/gfx/gfx.cpp b/firmware/common/libs/ssd1325/gfx/gfx.cpp similarity index 100% rename from firmware/common/libs/gfx/gfx.cpp rename to firmware/common/libs/ssd1325/gfx/gfx.cpp diff --git a/firmware/common/libs/gfx/gfx.h b/firmware/common/libs/ssd1325/gfx/gfx.h similarity index 100% rename from firmware/common/libs/gfx/gfx.h rename to firmware/common/libs/ssd1325/gfx/gfx.h diff --git a/firmware/common/libs/gfx/glcdfont.c b/firmware/common/libs/ssd1325/gfx/glcdfont.c similarity index 100% rename from firmware/common/libs/gfx/glcdfont.c rename to firmware/common/libs/ssd1325/gfx/glcdfont.c diff --git a/firmware/common/libs/gfx/license.txt b/firmware/common/libs/ssd1325/gfx/license.txt similarity index 100% rename from firmware/common/libs/gfx/license.txt rename to firmware/common/libs/ssd1325/gfx/license.txt From 811d1d25bccdc8400a65979430d57230ba9ea97d Mon Sep 17 00:00:00 2001 From: Austin Morlan Date: Wed, 18 Oct 2017 17:02:55 -0700 Subject: [PATCH 26/84] Move operator override DTC into DTC enums --- api/include/can_protocols/brake_can_protocol.h | 9 +++------ api/include/can_protocols/steering_can_protocol.h | 9 +++------ api/include/can_protocols/throttle_can_protocol.h | 9 +++------ 3 files changed, 9 insertions(+), 18 deletions(-) diff --git a/api/include/can_protocols/brake_can_protocol.h b/api/include/can_protocols/brake_can_protocol.h index d8e56b3d..2823ee3c 100644 --- a/api/include/can_protocols/brake_can_protocol.h +++ b/api/include/can_protocols/brake_can_protocol.h @@ -58,16 +58,13 @@ enum /* DTC bitfield position indicating an invalid sensor value. */ OSCC_BRAKE_DTC_INVALID_SENSOR_VAL = 0, + /* DTC bitfield position indicating an operator override. */ + OSCC_BRAKE_DTC_OPERATOR_OVERRIDE, + /* Number of possible brake DTCs. */ OSCC_BRAKE_DTC_COUNT }; -/* - * @brief Brake DTC bitfield position indicating an operator override. - * - */ -#define OSCC_BRAKE_DTC_OPERATOR_OVERRIDE (0x1) - #pragma pack(push) #pragma pack(1) diff --git a/api/include/can_protocols/steering_can_protocol.h b/api/include/can_protocols/steering_can_protocol.h index 5dfe5480..bfc17e24 100644 --- a/api/include/can_protocols/steering_can_protocol.h +++ b/api/include/can_protocols/steering_can_protocol.h @@ -58,16 +58,13 @@ enum /* DTC bitfield position indicating an invalid sensor value. */ OSCC_STEERING_DTC_INVALID_SENSOR_VAL = 0, + /* DTC bitfield position indicating an operator override. */ + OSCC_STEERING_DTC_OPERATOR_OVERRIDE, + /* Number of possible steering DTCs. */ OSCC_STEERING_DTC_COUNT }; -/* - * @brief Steering DTC bitfield position indicating an operator override. - * - */ -#define OSCC_STEERING_DTC_OPERATOR_OVERRIDE (0x1) - #pragma pack(push) #pragma pack(1) diff --git a/api/include/can_protocols/throttle_can_protocol.h b/api/include/can_protocols/throttle_can_protocol.h index 4cf7bb2d..466dd2ed 100644 --- a/api/include/can_protocols/throttle_can_protocol.h +++ b/api/include/can_protocols/throttle_can_protocol.h @@ -58,16 +58,13 @@ enum /* DTC bitfield position indicating an invalid sensor value. */ OSCC_THROTTLE_DTC_INVALID_SENSOR_VAL = 0, + /* DTC bitfield position indicating an operator override. */ + OSCC_THROTTLE_DTC_OPERATOR_OVERRIDE, + /* Number of possible throttle DTCs. */ OSCC_THROTTLE_DTC_COUNT }; -/* - * @brief Throttle DTC bitfield position indicating an operator override. - * - */ - #define OSCC_THROTTLE_DTC_OPERATOR_OVERRIDE (0x1) - #pragma pack(push) #pragma pack(1) From 4a1e520912639aee662a9fa7e93a39cdb77c2947 Mon Sep 17 00:00:00 2001 From: Austin Morlan Date: Wed, 18 Oct 2017 17:28:28 -0700 Subject: [PATCH 27/84] Do not register multiple button presses on single --- firmware/can_gateway/src/display.cpp | 9 +++++++-- 1 file changed, 7 insertions(+), 2 deletions(-) diff --git a/firmware/can_gateway/src/display.cpp b/firmware/can_gateway/src/display.cpp index 4beeea8c..9694d8d1 100644 --- a/firmware/can_gateway/src/display.cpp +++ b/firmware/can_gateway/src/display.cpp @@ -346,11 +346,16 @@ static void print_padded_number( const unsigned int number ) static void read_button( void ) { - bool button_val = g_display.readButton(); + static bool button_val_last = false; - if( button_val == true ) + bool button_val_current = g_display.readButton(); + + if( (button_val_current != button_val_last) // prevent multiple button presses + && (button_val_current == true) ) { g_display_state.current_screen = (screen_t)((g_display_state.current_screen + 1) % SCREEN_COUNT); } + + button_val_last = button_val_current; } From bcb5c44c01f442604842afd4d1db1dbd0b43b2d3 Mon Sep 17 00:00:00 2001 From: Austin Morlan Date: Wed, 18 Oct 2017 17:29:04 -0700 Subject: [PATCH 28/84] Add spacing to BRAKES line to line up statuses --- firmware/can_gateway/src/display.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/firmware/can_gateway/src/display.cpp b/firmware/can_gateway/src/display.cpp index 9694d8d1..60149697 100644 --- a/firmware/can_gateway/src/display.cpp +++ b/firmware/can_gateway/src/display.cpp @@ -184,7 +184,7 @@ static void display_status_screen( void ) g_display.setCursor( ORIGIN_X, BRAKE_STATUS_Y ); - g_display.print( "BRAKES: " ); + g_display.print( "BRAKES: " ); print_module_status( g_display_state.status_screen.brakes ); g_display.setCursor( ORIGIN_X, STEERING_STATUS_Y ); From 5ea3132617d644625fb8cce6e8e20937bea1bd4b Mon Sep 17 00:00:00 2001 From: Austin Morlan Date: Wed, 18 Oct 2017 17:29:37 -0700 Subject: [PATCH 29/84] Clear DTC screen when DTCs clear --- firmware/can_gateway/src/communications.cpp | 78 +++++++++++++++++---- 1 file changed, 63 insertions(+), 15 deletions(-) diff --git a/firmware/can_gateway/src/communications.cpp b/firmware/can_gateway/src/communications.cpp index 98822a9f..8589e128 100644 --- a/firmware/can_gateway/src/communications.cpp +++ b/firmware/can_gateway/src/communications.cpp @@ -67,6 +67,7 @@ static void parse_brake_report( uint8_t *data ) { oscc_brake_report_s *report = (oscc_brake_report_s *) data; + if ( report->enabled == 1 ) { g_display_state.status_screen.brakes = MODULE_STATUS_ENABLED; @@ -76,14 +77,29 @@ static void parse_brake_report( uint8_t *data ) g_display_state.status_screen.brakes = MODULE_STATUS_DISABLED; } - if( report->dtcs != 0 ) + + if ( report->dtcs != 0 ) { g_display_state.status_screen.brakes = MODULE_STATUS_ERROR; + } - if ( DTC_CHECK( report->dtcs, OSCC_BRAKE_DTC_INVALID_SENSOR_VAL ) != 0) - { - g_display_state.dtc_screen.brakes[OSCC_BRAKE_DTC_INVALID_SENSOR_VAL] = true; - } + + if ( DTC_CHECK(report->dtcs, OSCC_BRAKE_DTC_INVALID_SENSOR_VAL) != 0 ) + { + g_display_state.dtc_screen.brakes[OSCC_BRAKE_DTC_INVALID_SENSOR_VAL] = true; + } + else + { + g_display_state.dtc_screen.brakes[OSCC_BRAKE_DTC_INVALID_SENSOR_VAL] = false; + } + + if ( DTC_CHECK(report->dtcs, OSCC_BRAKE_DTC_OPERATOR_OVERRIDE) != 0 ) + { + g_display_state.dtc_screen.brakes[OSCC_BRAKE_DTC_OPERATOR_OVERRIDE] = true; + } + else + { + g_display_state.dtc_screen.brakes[OSCC_BRAKE_DTC_OPERATOR_OVERRIDE] = false; } } @@ -92,6 +108,7 @@ static void parse_steering_report( uint8_t *data ) { oscc_steering_report_s *report = (oscc_steering_report_s *) data; + if ( report->enabled == 1 ) { g_display_state.status_screen.steering = MODULE_STATUS_ENABLED; @@ -101,14 +118,29 @@ static void parse_steering_report( uint8_t *data ) g_display_state.status_screen.steering = MODULE_STATUS_DISABLED; } - if( report->dtcs != 0 ) + + if ( report->dtcs != 0 ) { g_display_state.status_screen.steering = MODULE_STATUS_ERROR; + } - if ( DTC_CHECK( report->dtcs, OSCC_STEERING_DTC_INVALID_SENSOR_VAL ) != 0) - { - g_display_state.dtc_screen.steering[OSCC_STEERING_DTC_INVALID_SENSOR_VAL] = true; - } + + if ( DTC_CHECK(report->dtcs, OSCC_STEERING_DTC_INVALID_SENSOR_VAL) != 0 ) + { + g_display_state.dtc_screen.steering[OSCC_STEERING_DTC_INVALID_SENSOR_VAL] = true; + } + else + { + g_display_state.dtc_screen.steering[OSCC_STEERING_DTC_INVALID_SENSOR_VAL] = false; + } + + if ( DTC_CHECK(report->dtcs, OSCC_STEERING_DTC_OPERATOR_OVERRIDE) != 0 ) + { + g_display_state.dtc_screen.steering[OSCC_STEERING_DTC_OPERATOR_OVERRIDE] = true; + } + else + { + g_display_state.dtc_screen.steering[OSCC_STEERING_DTC_OPERATOR_OVERRIDE] = false; } } @@ -117,6 +149,7 @@ static void parse_throttle_report( uint8_t *data ) { oscc_throttle_report_s *report = (oscc_throttle_report_s *) data; + if ( report->enabled == 1 ) { g_display_state.status_screen.throttle = MODULE_STATUS_ENABLED; @@ -126,13 +159,28 @@ static void parse_throttle_report( uint8_t *data ) g_display_state.status_screen.throttle = MODULE_STATUS_DISABLED; } - if( report->dtcs != 0 ) + + if ( report->dtcs != 0 ) { g_display_state.status_screen.throttle = MODULE_STATUS_ERROR; + } - if ( DTC_CHECK( report->dtcs, OSCC_THROTTLE_DTC_INVALID_SENSOR_VAL ) != 0) - { - g_display_state.dtc_screen.throttle[OSCC_THROTTLE_DTC_INVALID_SENSOR_VAL] = true; - } + + if ( DTC_CHECK(report->dtcs, OSCC_THROTTLE_DTC_INVALID_SENSOR_VAL) != 0 ) + { + g_display_state.dtc_screen.throttle[OSCC_THROTTLE_DTC_INVALID_SENSOR_VAL] = true; + } + else + { + g_display_state.dtc_screen.throttle[OSCC_THROTTLE_DTC_INVALID_SENSOR_VAL] = false; + } + + if ( DTC_CHECK(report->dtcs, OSCC_THROTTLE_DTC_OPERATOR_OVERRIDE) != 0 ) + { + g_display_state.dtc_screen.throttle[OSCC_THROTTLE_DTC_OPERATOR_OVERRIDE] = true; + } + else + { + g_display_state.dtc_screen.throttle[OSCC_THROTTLE_DTC_OPERATOR_OVERRIDE] = false; } } From 166f484318747fa9d62b711e177e1af9e48202f3 Mon Sep 17 00:00:00 2001 From: Austin Morlan Date: Wed, 18 Oct 2017 17:30:46 -0700 Subject: [PATCH 30/84] Add module report check --- firmware/can_gateway/src/main.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/firmware/can_gateway/src/main.cpp b/firmware/can_gateway/src/main.cpp index 32bc0c8b..72d9714a 100644 --- a/firmware/can_gateway/src/main.cpp +++ b/firmware/can_gateway/src/main.cpp @@ -31,6 +31,8 @@ int main( void ) { wdt_reset(); + check_for_module_reports( ); + republish_obd_frames_to_control_can_bus( ); } } From c1462daaadab82102d5b301d0825efc3149eef08 Mon Sep 17 00:00:00 2001 From: Robert Brown Date: Tue, 7 Nov 2017 13:26:45 -0800 Subject: [PATCH 31/84] Add ROSCCO information Prior to this commit OSCC did not have any information about ROSCCO. This commit fixes that by adding a link to ROSCCO and a short description of what it is. --- README.md | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/README.md b/README.md index 978412e0..b2af58fb 100644 --- a/README.md +++ b/README.md @@ -209,10 +209,15 @@ strange behavior while printing that does not occur otherwise. # 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) +We've also created a ROS node, that uses the OSCC API to interface with the firmware from ROS messages, allowing you to send commands and receive reports in ROS. + +[ROSCCO](https://github.com/PolySync/roscco) + # OSCC API **Open and close CAN channel to OSCC Control CAN.** From 716a8b3a3716c4cdaca9e17f60a81482a7ae6e01 Mon Sep 17 00:00:00 2001 From: Austin Morlan Date: Thu, 9 Nov 2017 10:07:06 -0800 Subject: [PATCH 32/84] Remove check for controller command timeouts Prior to this commit, there were checks to ensure that commands were received on a consistent basis when enabled, which often led to erroneous timeouts due to timing limitations in the Arduino hardware and CAN communication. The timeout check is unnecessary because the modules won't do anything if no commands are given to them. This commit removes the controller command timeouts. --- .../brake/kia_soul_ev/include/communications.h | 14 -------------- .../brake/kia_soul_ev/src/communications.cpp | 16 ---------------- firmware/brake/kia_soul_ev/src/timers.cpp | 2 -- .../tests/features/checking_faults.feature | 9 --------- .../step_definitions/checking_faults.cpp | 8 -------- .../kia_soul_petrol/include/communications.h | 13 ------------- .../brake/kia_soul_petrol/src/communications.cpp | 16 ---------------- firmware/brake/kia_soul_petrol/src/timers.cpp | 2 -- .../tests/features/checking_faults.feature | 9 --------- .../step_definitions/checking_faults.cpp | 8 -------- firmware/steering/include/communications.h | 14 -------------- firmware/steering/src/communications.cpp | 16 ---------------- firmware/steering/src/timers.cpp | 2 -- .../tests/features/checking_faults.feature | 9 --------- .../step_definitions/checking_faults.cpp | 8 -------- firmware/throttle/include/communications.h | 14 -------------- firmware/throttle/src/communications.cpp | 16 ---------------- firmware/throttle/src/timers.cpp | 2 -- .../tests/features/checking_faults.feature | 9 --------- .../step_definitions/checking_faults.cpp | 8 -------- 20 files changed, 195 deletions(-) diff --git a/firmware/brake/kia_soul_ev/include/communications.h b/firmware/brake/kia_soul_ev/include/communications.h index f672488c..3f703a39 100644 --- a/firmware/brake/kia_soul_ev/include/communications.h +++ b/firmware/brake/kia_soul_ev/include/communications.h @@ -35,20 +35,6 @@ void publish_brake_report( 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 // diff --git a/firmware/brake/kia_soul_ev/src/communications.cpp b/firmware/brake/kia_soul_ev/src/communications.cpp index bcaf61ea..974d4b7e 100644 --- a/firmware/brake/kia_soul_ev/src/communications.cpp +++ b/firmware/brake/kia_soul_ev/src/communications.cpp @@ -65,22 +65,6 @@ void publish_fault_report( void ) } -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; diff --git a/firmware/brake/kia_soul_ev/src/timers.cpp b/firmware/brake/kia_soul_ev/src/timers.cpp index 3179348e..19fb21be 100644 --- a/firmware/brake/kia_soul_ev/src/timers.cpp +++ b/firmware/brake/kia_soul_ev/src/timers.cpp @@ -35,8 +35,6 @@ static void check_for_faults( void ) { cli(); - check_for_controller_command_timeout( ); - check_for_sensor_faults( ); g_brake_command_timeout = true; diff --git a/firmware/brake/kia_soul_ev/tests/features/checking_faults.feature b/firmware/brake/kia_soul_ev/tests/features/checking_faults.feature index adc6533c..9e123ce2 100644 --- a/firmware/brake/kia_soul_ev/tests/features/checking_faults.feature +++ b/firmware/brake/kia_soul_ev/tests/features/checking_faults.feature @@ -22,15 +22,6 @@ Feature: Checking for faults 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 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 index b9bb0a51..093d2b8e 100644 --- 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 @@ -23,14 +23,6 @@ WHEN("^a sensor becomes permanently disconnected$") } -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); diff --git a/firmware/brake/kia_soul_petrol/include/communications.h b/firmware/brake/kia_soul_petrol/include/communications.h index cdfbda44..3f703a39 100644 --- a/firmware/brake/kia_soul_petrol/include/communications.h +++ b/firmware/brake/kia_soul_petrol/include/communications.h @@ -35,19 +35,6 @@ void publish_brake_report( 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 // diff --git a/firmware/brake/kia_soul_petrol/src/communications.cpp b/firmware/brake/kia_soul_petrol/src/communications.cpp index 08a3cc7a..c893e7a9 100644 --- a/firmware/brake/kia_soul_petrol/src/communications.cpp +++ b/firmware/brake/kia_soul_petrol/src/communications.cpp @@ -66,22 +66,6 @@ void publish_fault_report( void ) } -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 - controller command" ); - } - } -} - - void check_for_incoming_message( void ) { can_frame_s rx_frame; diff --git a/firmware/brake/kia_soul_petrol/src/timers.cpp b/firmware/brake/kia_soul_petrol/src/timers.cpp index bec06cac..64f9928c 100644 --- a/firmware/brake/kia_soul_petrol/src/timers.cpp +++ b/firmware/brake/kia_soul_petrol/src/timers.cpp @@ -35,8 +35,6 @@ static void check_for_faults( void ) { cli(); - check_for_controller_command_timeout( ); - check_for_sensor_faults( ); g_brake_command_timeout = true; diff --git a/firmware/brake/kia_soul_petrol/tests/features/checking_faults.feature b/firmware/brake/kia_soul_petrol/tests/features/checking_faults.feature index 5230dd8f..3c036eeb 100644 --- a/firmware/brake/kia_soul_petrol/tests/features/checking_faults.feature +++ b/firmware/brake/kia_soul_petrol/tests/features/checking_faults.feature @@ -24,15 +24,6 @@ Feature: Timeouts and overrides 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 diff --git a/firmware/brake/kia_soul_petrol/tests/features/step_definitions/checking_faults.cpp b/firmware/brake/kia_soul_petrol/tests/features/step_definitions/checking_faults.cpp index 9581dbfa..f0b078c2 100644 --- a/firmware/brake/kia_soul_petrol/tests/features/step_definitions/checking_faults.cpp +++ b/firmware/brake/kia_soul_petrol/tests/features/step_definitions/checking_faults.cpp @@ -24,14 +24,6 @@ WHEN("^a sensor becomes permanently disconnected$") } -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 brake pedal$") { REGEX_PARAM(int, pedal_val); diff --git a/firmware/steering/include/communications.h b/firmware/steering/include/communications.h index 78e5f6b9..df7d2c0d 100644 --- a/firmware/steering/include/communications.h +++ b/firmware/steering/include/communications.h @@ -35,20 +35,6 @@ void publish_steering_report( 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 // diff --git a/firmware/steering/src/communications.cpp b/firmware/steering/src/communications.cpp index 546ba870..d889fa30 100644 --- a/firmware/steering/src/communications.cpp +++ b/firmware/steering/src/communications.cpp @@ -65,22 +65,6 @@ void publish_fault_report( void ) } -void check_for_controller_command_timeout( void ) -{ - if( g_steering_control_state.enabled == true ) - { - if( g_steering_command_timeout == true ) - { - disable_control( ); - - publish_fault_report( ); - - DEBUG_PRINTLN( "Timeout - controller command" ); - } - } -} - - void check_for_incoming_message( void ) { can_frame_s rx_frame; diff --git a/firmware/steering/src/timers.cpp b/firmware/steering/src/timers.cpp index d169791b..d627bbd8 100644 --- a/firmware/steering/src/timers.cpp +++ b/firmware/steering/src/timers.cpp @@ -35,8 +35,6 @@ static void check_for_faults( void ) { cli(); - check_for_controller_command_timeout( ); - check_for_sensor_faults( ); g_steering_command_timeout = true; diff --git a/firmware/steering/tests/features/checking_faults.feature b/firmware/steering/tests/features/checking_faults.feature index ef696630..12f057ce 100644 --- a/firmware/steering/tests/features/checking_faults.feature +++ b/firmware/steering/tests/features/checking_faults.feature @@ -22,15 +22,6 @@ Feature: Checking for faults And a fault report should be published - Scenario: Controller command timeout - Given steering 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 steering control is enabled diff --git a/firmware/steering/tests/features/step_definitions/checking_faults.cpp b/firmware/steering/tests/features/step_definitions/checking_faults.cpp index 2dc4867d..1c5df5b7 100644 --- a/firmware/steering/tests/features/step_definitions/checking_faults.cpp +++ b/firmware/steering/tests/features/step_definitions/checking_faults.cpp @@ -24,14 +24,6 @@ WHEN("^a sensor becomes permanently disconnected$") } -WHEN("^the time since the last received controller command exceeds the timeout$") -{ - g_steering_command_timeout = true; - - check_for_controller_command_timeout(); -} - - WHEN("^the operator applies (.*) to the steering wheel$") { REGEX_PARAM(int, steering_sensor_val); diff --git a/firmware/throttle/include/communications.h b/firmware/throttle/include/communications.h index 4fd150e8..218551be 100644 --- a/firmware/throttle/include/communications.h +++ b/firmware/throttle/include/communications.h @@ -35,20 +35,6 @@ void publish_throttle_report( 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 // diff --git a/firmware/throttle/src/communications.cpp b/firmware/throttle/src/communications.cpp index 1f0d8645..4c65810d 100644 --- a/firmware/throttle/src/communications.cpp +++ b/firmware/throttle/src/communications.cpp @@ -65,22 +65,6 @@ void publish_fault_report( void ) } -void check_for_controller_command_timeout( void ) -{ - if( g_throttle_control_state.enabled == true ) - { - if( g_throttle_command_timeout == true ) - { - disable_control( ); - - publish_fault_report( ); - - DEBUG_PRINTLN( "Timeout - controller command" ); - } - } -} - - void check_for_incoming_message( void ) { can_frame_s rx_frame; diff --git a/firmware/throttle/src/timers.cpp b/firmware/throttle/src/timers.cpp index a93cbaba..daeea326 100644 --- a/firmware/throttle/src/timers.cpp +++ b/firmware/throttle/src/timers.cpp @@ -35,8 +35,6 @@ static void check_for_faults( void ) { cli(); - check_for_controller_command_timeout( ); - check_for_sensor_faults( ); g_throttle_command_timeout = true; diff --git a/firmware/throttle/tests/features/checking_faults.feature b/firmware/throttle/tests/features/checking_faults.feature index 18d6c43a..e046efc8 100644 --- a/firmware/throttle/tests/features/checking_faults.feature +++ b/firmware/throttle/tests/features/checking_faults.feature @@ -22,15 +22,6 @@ Feature: Checking for faults And a fault report should be published - Scenario: Controller command timeout - Given throttle 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 throttle control is enabled diff --git a/firmware/throttle/tests/features/step_definitions/checking_faults.cpp b/firmware/throttle/tests/features/step_definitions/checking_faults.cpp index 0a09c09f..3034a21f 100644 --- a/firmware/throttle/tests/features/step_definitions/checking_faults.cpp +++ b/firmware/throttle/tests/features/step_definitions/checking_faults.cpp @@ -24,14 +24,6 @@ WHEN("^a sensor becomes permanently disconnected$") } -WHEN("^the time since the last received controller command exceeds the timeout$") -{ - g_throttle_command_timeout = true; - - check_for_controller_command_timeout(); -} - - WHEN("^the operator applies (.*) to the accelerator$") { REGEX_PARAM(int, throttle_sensor_val); From 7d90cf9fbb25203061c6054a2873032c2b995942 Mon Sep 17 00:00:00 2001 From: Austin Morlan Date: Thu, 9 Nov 2017 10:13:57 -0800 Subject: [PATCH 33/84] Update vehicle date range --- README.md | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/README.md b/README.md index 978412e0..37fef674 100644 --- a/README.md +++ b/README.md @@ -95,7 +95,7 @@ cmake .. -DKIA_SOUL=ON 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. +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. @@ -420,7 +420,7 @@ make run-all-tests # Additional Vehicles & Contributing -OSCC currently has information regarding the Kia Soul PS (2014-2016), but we want to grow! The +OSCC currently has information regarding the Kia Soul PS (2014-2018), 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 From 0ee68074236dce9a5aa9a0fb1b705a099ca15b59 Mon Sep 17 00:00:00 2001 From: Austin Morlan Date: Thu, 9 Nov 2017 10:19:45 -0800 Subject: [PATCH 34/84] Add list of possible vehicle build flags --- README.md | 12 ++++++++++-- 1 file changed, 10 insertions(+), 2 deletions(-) diff --git a/README.md b/README.md index 37fef674..ef02a45b 100644 --- a/README.md +++ b/README.md @@ -82,8 +82,16 @@ mkdir build cd build ``` -To generate Makefiles, tell `cmake` which platform to build firmware for. For example, if you want to build -firmware for the Kia Soul: +To generate Makefiles, tell `cmake` which vehicle to build for by supplying the +appropriate build flag: + +| Vehicle | Flag | +| --------------- | ---------------- | +| Kia Soul Petrol | -DKIA_SOUL=ON | +| Kia Soul EV | -DKIA_SOUL_EV=ON | + + +For example, if you want to build firmware for the petrol Kia Soul: ``` cmake .. -DKIA_SOUL=ON From 48a6187b202190595213d1e4c56ff7fad56003cc Mon Sep 17 00:00:00 2001 From: Chris Otos Date: Fri, 17 Nov 2017 15:21:46 -0800 Subject: [PATCH 35/84] Fix display initialization error Prior to this commit the display would not consistantly get initialized. The display's red led would be lit with a blank display. This commit moved the display initalization to happen before initializing the CAN buses. Tested by cycling power several times, running joysick commander, and verifying the display correctly reports when the system is enabled of disabled. --- firmware/can_gateway/src/init.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/firmware/can_gateway/src/init.cpp b/firmware/can_gateway/src/init.cpp index 43be5b53..b58e1579 100644 --- a/firmware/can_gateway/src/init.cpp +++ b/firmware/can_gateway/src/init.cpp @@ -26,12 +26,12 @@ void init_communication_interfaces( void ) init_serial(); #endif + DEBUG_PRINTLN( "init display"); + init_display( ); + DEBUG_PRINT( "init OBD CAN - "); init_can( g_obd_can ); DEBUG_PRINT( "init Control CAN - "); init_can( g_control_can ); - - DEBUG_PRINTLN( "init display"); - init_display( ); } From 66e10fce4b8b20922dd7da913c8e543548b6e24c Mon Sep 17 00:00:00 2001 From: Chris Otos Date: Fri, 17 Nov 2017 16:27:35 -0800 Subject: [PATCH 36/84] Fix failing gateway test --- firmware/can_gateway/include/globals.h | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/firmware/can_gateway/include/globals.h b/firmware/can_gateway/include/globals.h index 3f61436f..92c3f758 100644 --- a/firmware/can_gateway/include/globals.h +++ b/firmware/can_gateway/include/globals.h @@ -37,7 +37,9 @@ #ifdef GLOBAL_DEFINED MCP_CAN g_obd_can( PIN_OBD_CAN_CHIP_SELECT ); MCP_CAN g_control_can( PIN_CONTROL_CAN_CHIP_SELECT ); - SSD1325 g_display( PIN_DISPLAY_CHIP_SELECT ); + #ifdef TESTS + SSD1325 g_display( PIN_DISPLAY_CHIP_SELECT ); + #endif #define EXTERN #else From 3c712932519af6c36728eb8f671aa5ac4f3f7455 Mon Sep 17 00:00:00 2001 From: Chris Otos Date: Fri, 17 Nov 2017 16:35:28 -0800 Subject: [PATCH 37/84] changed ifdef to ifndef --- firmware/can_gateway/include/globals.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/firmware/can_gateway/include/globals.h b/firmware/can_gateway/include/globals.h index 92c3f758..a561306f 100644 --- a/firmware/can_gateway/include/globals.h +++ b/firmware/can_gateway/include/globals.h @@ -37,7 +37,7 @@ #ifdef GLOBAL_DEFINED MCP_CAN g_obd_can( PIN_OBD_CAN_CHIP_SELECT ); MCP_CAN g_control_can( PIN_CONTROL_CAN_CHIP_SELECT ); - #ifdef TESTS + #ifndef TESTS SSD1325 g_display( PIN_DISPLAY_CHIP_SELECT ); #endif From 8ea69b2e01250b0641133342d55697840de6b23d Mon Sep 17 00:00:00 2001 From: Chris Otos Date: Fri, 17 Nov 2017 16:42:31 -0800 Subject: [PATCH 38/84] Add add_definitions to CMakeLists.txt --- firmware/CMakeLists.txt | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/firmware/CMakeLists.txt b/firmware/CMakeLists.txt index 8c6d6c7b..649a5c6d 100644 --- a/firmware/CMakeLists.txt +++ b/firmware/CMakeLists.txt @@ -3,6 +3,10 @@ if(TESTS) project(tests) + if(TESTS) + add_definitions(-DTESTS) + endif() + if(DEBUG) add_definitions(-DDEBUG) endif() From d9b972447a418b29d166d1b8d3d5f832b37df203 Mon Sep 17 00:00:00 2001 From: Austin Morlan Date: Tue, 5 Dec 2017 10:54:05 -0800 Subject: [PATCH 39/84] Update README with links to reports --- README.md | 7 +++++++ 1 file changed, 7 insertions(+) diff --git a/README.md b/README.md index 43d5a216..ba4d4431 100644 --- a/README.md +++ b/README.md @@ -286,6 +286,13 @@ In order to receive reports from the modules, your application will need to regi 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. +Each module's reports are described in their respective wiki sections: + +* [Brake (EV)](https://github.com/PolySync/oscc/wiki/Firmware-Brake-%28EV%29#brake-report) +* [Brake (Petrol)](https://github.com/PolySync/oscc/wiki/Firmware-Brake-%28Petrol%29#brake-report) +* [Steering](https://github.com/PolySync/oscc/wiki/Firmware-Steering#steering-report) +* [Throttle](https://github.com/PolySync/oscc/wiki/Firmware-Throttle#throttle-report) + 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. From f8430b1bd19170d840787e443f1ba40342d66102 Mon Sep 17 00:00:00 2001 From: Austin Morlan Date: Thu, 14 Dec 2017 11:05:32 -0800 Subject: [PATCH 40/84] Renumber CAN message IDs to be grouped by module Prior to this commit, the CAN message IDs were not grouped by module making filtering of CAN messages per module more difficult. This commit assigns each module a range of 16 CAN IDs for easy filtering in the future. --- api/include/can_protocols/brake_can_protocol.h | 11 +++++++++-- api/include/can_protocols/steering_can_protocol.h | 15 +++++++++++---- api/include/can_protocols/throttle_can_protocol.h | 15 +++++++++++---- 3 files changed, 31 insertions(+), 10 deletions(-) diff --git a/api/include/can_protocols/brake_can_protocol.h b/api/include/can_protocols/brake_can_protocol.h index 2823ee3c..d9309e33 100644 --- a/api/include/can_protocols/brake_can_protocol.h +++ b/api/include/can_protocols/brake_can_protocol.h @@ -13,6 +13,13 @@ #include "magic.h" +/* + * @brief CAN ID representing the range of brake messages. + * + */ +#define OSCC_BRAKE_CAN_ID_INDEX (0x50) + + /* * @brief Brake enable message (CAN frame) ID. * @@ -29,13 +36,13 @@ * @brief Brake command message (CAN frame) ID. * */ -#define OSCC_BRAKE_COMMAND_CAN_ID (0x60) +#define OSCC_BRAKE_COMMAND_CAN_ID (0x52) /* * @brief Brake report message (CAN frame) ID. * */ -#define OSCC_BRAKE_REPORT_CAN_ID (0x61) +#define OSCC_BRAKE_REPORT_CAN_ID (0x53) /* * @brief Brake report message (CAN frame) length. diff --git a/api/include/can_protocols/steering_can_protocol.h b/api/include/can_protocols/steering_can_protocol.h index bfc17e24..df47f2dc 100644 --- a/api/include/can_protocols/steering_can_protocol.h +++ b/api/include/can_protocols/steering_can_protocol.h @@ -13,29 +13,36 @@ #include "magic.h" +/* + * @brief CAN ID representing the range of steering messages. + * + */ +#define OSCC_STEERING_CAN_ID_INDEX (0x60) + + /* * @brief Steering enable message (CAN frame) ID. * */ -#define OSCC_STEERING_ENABLE_CAN_ID (0x54) +#define OSCC_STEERING_ENABLE_CAN_ID (0x60) /* * @brief Steering disable message (CAN frame) ID. * */ -#define OSCC_STEERING_DISABLE_CAN_ID (0x55) +#define OSCC_STEERING_DISABLE_CAN_ID (0x61) /* * @brief Steering command message (CAN frame) ID. * */ -#define OSCC_STEERING_COMMAND_CAN_ID (0x64) +#define OSCC_STEERING_COMMAND_CAN_ID (0x62) /* * @brief Steering report message (CAN frame) ID. * */ -#define OSCC_STEERING_REPORT_CAN_ID (0x65) +#define OSCC_STEERING_REPORT_CAN_ID (0x63) /* * @brief Steering report message (CAN frame) length. diff --git a/api/include/can_protocols/throttle_can_protocol.h b/api/include/can_protocols/throttle_can_protocol.h index 466dd2ed..cc2abbb9 100644 --- a/api/include/can_protocols/throttle_can_protocol.h +++ b/api/include/can_protocols/throttle_can_protocol.h @@ -13,29 +13,36 @@ #include "magic.h" +/* + * @brief CAN ID representing the range of throttle messages. + * + */ +#define OSCC_THROTTLE_CAN_ID_INDEX (0x70) + + /* * @brief Throttle enable message (CAN frame) ID. * */ -#define OSCC_THROTTLE_ENABLE_CAN_ID (0x52) +#define OSCC_THROTTLE_ENABLE_CAN_ID (0x70) /* * @brief Throttle disable message (CAN frame) ID. * */ -#define OSCC_THROTTLE_DISABLE_CAN_ID (0x53) +#define OSCC_THROTTLE_DISABLE_CAN_ID (0x71) /* * @brief Throttle command message (CAN frame) ID. * */ -#define OSCC_THROTTLE_COMMAND_CAN_ID (0x62) +#define OSCC_THROTTLE_COMMAND_CAN_ID (0x72) /* * @brief Throttle report message (CAN frame) ID. * */ -#define OSCC_THROTTLE_REPORT_CAN_ID (0x63) +#define OSCC_THROTTLE_REPORT_CAN_ID (0x73) /* * @brief Throttle report message (CAN frame) length. From 52e3a6702913479d1cb377055ea14eb5d2db142c Mon Sep 17 00:00:00 2001 From: Austin Morlan Date: Thu, 14 Dec 2017 11:07:42 -0800 Subject: [PATCH 41/84] Move fault message into a global messages file Prior to this commit, the fault message got its own file with the single fault report message inside of it. This commit creates a global CAN protocol file that contains the fault report for now but will contain other global messages in the future. This keeps them all within the same range, allowing for easy filtering. --- ...t_can_protocol.h => global_can_protocol.h} | 19 +- .../brake/kia_soul_ev/src/communications.cpp | 2 +- .../features/step_definitions/common.cpp | 2 +- .../tests/property/include/wrapper.hpp | 2 +- .../kia_soul_petrol/src/communications.cpp | 2 +- .../features/step_definitions/common.cpp | 2 +- firmware/steering/src/communications.cpp | 2 +- .../features/step_definitions/common.cpp | 2 +- .../tests/property/include/wrapper.hpp | 2 +- firmware/throttle/src/communications.1.cpp | 222 ++++++++++++++++++ firmware/throttle/src/communications.cpp | 2 +- .../features/step_definitions/common.cpp | 2 +- .../tests/property/include/wrapper.hpp | 2 +- 13 files changed, 246 insertions(+), 17 deletions(-) rename api/include/can_protocols/{fault_can_protocol.h => global_can_protocol.h} (74%) create mode 100644 firmware/throttle/src/communications.1.cpp diff --git a/api/include/can_protocols/fault_can_protocol.h b/api/include/can_protocols/global_can_protocol.h similarity index 74% rename from api/include/can_protocols/fault_can_protocol.h rename to api/include/can_protocols/global_can_protocol.h index f8922174..fc2ec44b 100644 --- a/api/include/can_protocols/fault_can_protocol.h +++ b/api/include/can_protocols/global_can_protocol.h @@ -1,22 +1,29 @@ /** - * @file fault_can_protocol.h - * @brief Fault CAN Protocol. + * @file global_can_protocol.h + * @brief Global CAN Protocol. * */ -#ifndef _OSCC_FAULT_CAN_PROTOCOL_H_ -#define _OSCC_FAULT_CAN_PROTOCOL_H_ +#ifndef _OSCC_GLOBAL_CAN_PROTOCOL_H_ +#define _OSCC_GLOBAL_CAN_PROTOCOL_H_ #include #include "magic.h" + +/* + * @brief CAN ID representing the range of global messages. + * + */ +#define OSCC_GLOBAL_CAN_ID_INDEX (0x90) + /* * @brief Fault report message (CAN frame) ID. * */ -#define OSCC_FAULT_REPORT_CAN_ID (0x99) +#define OSCC_FAULT_REPORT_CAN_ID (0x9F) /* * @brief Fault report message (CAN frame) length. @@ -58,4 +65,4 @@ typedef struct #pragma pack(pop) -#endif /* _OSCC_FAULT_CAN_PROTOCOL_H_ */ +#endif /* _OSCC_GLOBAL_CAN_PROTOCOL_H_ */ diff --git a/firmware/brake/kia_soul_ev/src/communications.cpp b/firmware/brake/kia_soul_ev/src/communications.cpp index bcaf61ea..7ea31ae6 100644 --- a/firmware/brake/kia_soul_ev/src/communications.cpp +++ b/firmware/brake/kia_soul_ev/src/communications.cpp @@ -7,7 +7,7 @@ #include #include "can_protocols/brake_can_protocol.h" -#include "can_protocols/fault_can_protocol.h" +#include "can_protocols/global_can_protocol.h" #include "brake_control.h" #include "communications.h" #include "debug.h" 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 index 035acca1..50877651 100644 --- a/firmware/brake/kia_soul_ev/tests/features/step_definitions/common.cpp +++ b/firmware/brake/kia_soul_ev/tests/features/step_definitions/common.cpp @@ -9,7 +9,7 @@ #include "oscc_can.h" #include "mcp_can.h" #include "brake_control.h" -#include "can_protocols/fault_can_protocol.h" +#include "can_protocols/global_can_protocol.h" #include "can_protocols/brake_can_protocol.h" #include "globals.h" diff --git a/firmware/brake/kia_soul_ev/tests/property/include/wrapper.hpp b/firmware/brake/kia_soul_ev/tests/property/include/wrapper.hpp index 8f73c05b..50eda86b 100644 --- a/firmware/brake/kia_soul_ev/tests/property/include/wrapper.hpp +++ b/firmware/brake/kia_soul_ev/tests/property/include/wrapper.hpp @@ -3,5 +3,5 @@ #include "brake_control.h" #include "oscc_can.h" #include "can_protocols/brake_can_protocol.h" -#include "can_protocols/fault_can_protocol.h" +#include "can_protocols/global_can_protocol.h" #include "vehicles.h" diff --git a/firmware/brake/kia_soul_petrol/src/communications.cpp b/firmware/brake/kia_soul_petrol/src/communications.cpp index 08a3cc7a..64067e3f 100644 --- a/firmware/brake/kia_soul_petrol/src/communications.cpp +++ b/firmware/brake/kia_soul_petrol/src/communications.cpp @@ -9,7 +9,7 @@ #include "brake_control.h" #include "can_protocols/brake_can_protocol.h" -#include "can_protocols/fault_can_protocol.h" +#include "can_protocols/global_can_protocol.h" #include "communications.h" #include "debug.h" #include "globals.h" diff --git a/firmware/brake/kia_soul_petrol/tests/features/step_definitions/common.cpp b/firmware/brake/kia_soul_petrol/tests/features/step_definitions/common.cpp index db167b02..321dff4e 100644 --- a/firmware/brake/kia_soul_petrol/tests/features/step_definitions/common.cpp +++ b/firmware/brake/kia_soul_petrol/tests/features/step_definitions/common.cpp @@ -10,7 +10,7 @@ #include "mcp_can.h" #include "brake_control.h" #include "can_protocols/brake_can_protocol.h" -#include "can_protocols/fault_can_protocol.h" +#include "can_protocols/global_can_protocol.h" #include "vehicles.h" #include "globals.h" diff --git a/firmware/steering/src/communications.cpp b/firmware/steering/src/communications.cpp index 546ba870..50bb095e 100644 --- a/firmware/steering/src/communications.cpp +++ b/firmware/steering/src/communications.cpp @@ -6,7 +6,7 @@ #include -#include "can_protocols/fault_can_protocol.h" +#include "can_protocols/global_can_protocol.h" #include "can_protocols/steering_can_protocol.h" #include "communications.h" #include "debug.h" diff --git a/firmware/steering/tests/features/step_definitions/common.cpp b/firmware/steering/tests/features/step_definitions/common.cpp index 09fcfada..25aed3f9 100644 --- a/firmware/steering/tests/features/step_definitions/common.cpp +++ b/firmware/steering/tests/features/step_definitions/common.cpp @@ -9,7 +9,7 @@ #include "oscc_can.h" #include "mcp_can.h" #include "steering_control.h" -#include "can_protocols/fault_can_protocol.h" +#include "can_protocols/global_can_protocol.h" #include "can_protocols/steering_can_protocol.h" #include "globals.h" diff --git a/firmware/steering/tests/property/include/wrapper.hpp b/firmware/steering/tests/property/include/wrapper.hpp index 1b412155..edbd987d 100644 --- a/firmware/steering/tests/property/include/wrapper.hpp +++ b/firmware/steering/tests/property/include/wrapper.hpp @@ -3,5 +3,5 @@ #include "steering_control.h" #include "oscc_can.h" #include "can_protocols/steering_can_protocol.h" -#include "can_protocols/fault_can_protocol.h" +#include "can_protocols/global_can_protocol.h" #include "vehicles.h" diff --git a/firmware/throttle/src/communications.1.cpp b/firmware/throttle/src/communications.1.cpp new file mode 100644 index 00000000..af44c386 --- /dev/null +++ b/firmware/throttle/src/communications.1.cpp @@ -0,0 +1,222 @@ +/** + * @file communications.cpp + * + */ + + +#include + +#include "can_protocols/global_can_protocol.h" +#include "can_protocols/throttle_can_protocol.h" +#include "communications.h" +#include "debug.h" +#include "globals.h" +#include "mcp_can.h" +#include "oscc_can.h" +// #include "oscc_eeprom.h" +#include "throttle_control.h" + + +static void process_rx_frame( + const can_frame_s * const frame ); + +static void process_throttle_command( + const uint8_t * const data ); + +static void process_fault_report( + const uint8_t * const data ); + +static void process_config_u16( + const uint8_t * const data ); + +static void process_config_f32( + const uint8_t * const data ); + + +void publish_throttle_report( void ) +{ + oscc_throttle_report_s throttle_report; + + throttle_report.magic[0] = (uint8_t) OSCC_MAGIC_BYTE_0; + throttle_report.magic[1] = (uint8_t) OSCC_MAGIC_BYTE_1; + throttle_report.enabled = (uint8_t) g_throttle_control_state.enabled; + throttle_report.operator_override = (uint8_t) g_throttle_control_state.operator_override; + throttle_report.dtcs = g_throttle_control_state.dtcs; + + cli(); + g_control_can.sendMsgBuf( + OSCC_THROTTLE_REPORT_CAN_ID, + CAN_STANDARD, + OSCC_THROTTLE_REPORT_CAN_DLC, + (uint8_t*) &throttle_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_THROTTLE; + fault_report.dtcs = g_throttle_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_throttle_control_state.enabled == true ) + { + if( g_throttle_command_timeout == true ) + { + disable_control( ); + + publish_fault_report( ); + + DEBUG_PRINTLN( "Timeout - 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 ) + { + Serial.println(frame->id, 16); + + // if( (frame->data[0] == OSCC_MAGIC_BYTE_0) + // && (frame->data[1] == OSCC_MAGIC_BYTE_1) ) + // { + // 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 ); + // } + // else if ( frame->id == OSCC_FAULT_REPORT_CAN_ID ) + // { + // process_fault_report( frame-> data ); + // } + // else if ( frame->id == OSCC_CONFIG_F32_CAN_ID ) + // { + // process_config_f32( frame->data ); + // } + // else if ( frame->id == OSCC_CONFIG_U16_CAN_ID ) + // { + // process_config_u16( frame->data ); + // } + // } + } +} + + +static void process_throttle_command( + const uint8_t * const data ) +{ + if ( data != NULL ) + { + const oscc_throttle_command_s * const throttle_command = + (oscc_throttle_command_s *) data; + + update_throttle( + throttle_command->spoof_value_high, + throttle_command->spoof_value_low ); + + g_throttle_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 ); + } +} + + +static void process_config_u16( + const uint8_t * const data ) +{ + // if ( data != NULL ) + // { + // const oscc_config_u16_s * const config = + // (oscc_config_u16_s *) data; + + // if ( (config->name == OSCC_CONFIG_U16_THROTTLE_PEDAL_OVERRIDE_THRESHOLD) + // || (config->name == OSCC_CONFIG_U16_THROTTLE_FAULT_CHECK_FREQUENCY_IN_HZ) ) + // { + // Serial.print("n "); + // Serial.print(config->name); + // Serial.print(";v "); + // Serial.println(config->value); + // oscc_eeprom_write_u16( config->name, config->value ); + + // uint16_t val = oscc_eeprom_read_u16( config->name ); + + // Serial.println(val); + // } + // } +} + + +static void process_config_f32( + const uint8_t * const data ) +{ + // if ( data != NULL ) + // { + // const oscc_config_f32_s * const config = + // (oscc_config_f32_s *) data; + + // if ( (config->name == OSCC_CONFIG_F32_THROTTLE_SPOOF_LOW_SIGNAL_VOLTAGE_MIN) + // || (config->name == OSCC_CONFIG_F32_THROTTLE_SPOOF_LOW_SIGNAL_VOLTAGE_MAX) + // || (config->name == OSCC_CONFIG_F32_THROTTLE_SPOOF_HIGH_SIGNAL_VOLTAGE_MIN) + // || (config->name == OSCC_CONFIG_F32_THROTTLE_SPOOF_HIGH_SIGNAL_VOLTAGE_MAX) ) + // { + // oscc_eeprom_write_f32( config->name, config->value ); + + // float val = oscc_eeprom_read_f32( config->name ); + + // Serial.println(val); + // } + // } +} diff --git a/firmware/throttle/src/communications.cpp b/firmware/throttle/src/communications.cpp index 1f0d8645..abe7a279 100644 --- a/firmware/throttle/src/communications.cpp +++ b/firmware/throttle/src/communications.cpp @@ -6,7 +6,7 @@ #include -#include "can_protocols/fault_can_protocol.h" +#include "can_protocols/global_can_protocol.h" #include "can_protocols/throttle_can_protocol.h" #include "communications.h" #include "debug.h" diff --git a/firmware/throttle/tests/features/step_definitions/common.cpp b/firmware/throttle/tests/features/step_definitions/common.cpp index a2636b08..0ca66179 100644 --- a/firmware/throttle/tests/features/step_definitions/common.cpp +++ b/firmware/throttle/tests/features/step_definitions/common.cpp @@ -9,7 +9,7 @@ #include "oscc_can.h" #include "mcp_can.h" #include "throttle_control.h" -#include "can_protocols/fault_can_protocol.h" +#include "can_protocols/global_can_protocol.h" #include "can_protocols/throttle_can_protocol.h" #include "globals.h" diff --git a/firmware/throttle/tests/property/include/wrapper.hpp b/firmware/throttle/tests/property/include/wrapper.hpp index 02fd161d..a6b1ef5b 100644 --- a/firmware/throttle/tests/property/include/wrapper.hpp +++ b/firmware/throttle/tests/property/include/wrapper.hpp @@ -3,5 +3,5 @@ #include "throttle_control.h" #include "oscc_can.h" #include "can_protocols/throttle_can_protocol.h" -#include "can_protocols/fault_can_protocol.h" +#include "can_protocols/global_can_protocol.h" #include "vehicles.h" From 472122d01c9ed7f2f2bd96b98e09857f80417289 Mon Sep 17 00:00:00 2001 From: Austin Morlan Date: Thu, 14 Dec 2017 12:00:29 -0800 Subject: [PATCH 42/84] Add CAN filtering for module-specific messages Prior to this commit, there was no filtering being done on received CAN messages by the CAN transceiver, so the MCU had to service every CAN frame that appeared on the bus. This commit adds filtering to each module so that it only sees messages that are pertinent to its operation, reducing MCU load. --- firmware/brake/kia_soul_ev/src/init.cpp | 7 +++++++ firmware/brake/kia_soul_petrol/src/init.cpp | 7 +++++++ firmware/steering/src/init.cpp | 7 +++++++ firmware/throttle/src/init.cpp | 7 +++++++ 4 files changed, 28 insertions(+) diff --git a/firmware/brake/kia_soul_ev/src/init.cpp b/firmware/brake/kia_soul_ev/src/init.cpp index 39a0401e..6b5bab9c 100644 --- a/firmware/brake/kia_soul_ev/src/init.cpp +++ b/firmware/brake/kia_soul_ev/src/init.cpp @@ -7,6 +7,7 @@ #include #include "can_protocols/brake_can_protocol.h" +#include "can_protocols/global_can_protocol.h" #include "communications.h" #include "debug.h" #include "globals.h" @@ -51,4 +52,10 @@ void init_communication_interfaces( void ) DEBUG_PRINT( "init Control CAN - " ); init_can( g_control_can ); + + // Filter CAN messages - accept if (CAN_ID & mask) == (filter & mask) + g_control_can.init_Mask(0, 0, 0x7F0); // Filter for 0x0N0 to 0x0NF + g_control_can.init_Mask(1, 0, 0x7FF); // Don't use second filter + g_control_can.init_Filt(0, 0, OSCC_BRAKE_CAN_ID_INDEX); + g_control_can.init_Filt(1, 0, OSCC_GLOBAL_CAN_ID_INDEX); } diff --git a/firmware/brake/kia_soul_petrol/src/init.cpp b/firmware/brake/kia_soul_petrol/src/init.cpp index 20352326..e033a12d 100644 --- a/firmware/brake/kia_soul_petrol/src/init.cpp +++ b/firmware/brake/kia_soul_petrol/src/init.cpp @@ -9,6 +9,7 @@ #include "accumulator.h" #include "brake_control.h" #include "can_protocols/brake_can_protocol.h" +#include "can_protocols/global_can_protocol.h" #include "communications.h" #include "debug.h" #include "globals.h" @@ -61,4 +62,10 @@ void init_communication_interfaces( void ) DEBUG_PRINT( "init Control CAN - " ); init_can( g_control_can ); + + // Filter CAN messages - accept if (CAN_ID & mask) == (filter & mask) + g_control_can.init_Mask(0, 0, 0x7F0); // Filter for 0x0N0 to 0x0NF + g_control_can.init_Mask(1, 0, 0x7FF); // Don't use second filter + g_control_can.init_Filt(0, 0, OSCC_BRAKE_CAN_ID_INDEX); + g_control_can.init_Filt(1, 0, OSCC_GLOBAL_CAN_ID_INDEX); } diff --git a/firmware/steering/src/init.cpp b/firmware/steering/src/init.cpp index 500e0878..e2271f55 100644 --- a/firmware/steering/src/init.cpp +++ b/firmware/steering/src/init.cpp @@ -6,6 +6,7 @@ #include +#include "can_protocols/global_can_protocol.h" #include "can_protocols/steering_can_protocol.h" #include "communications.h" #include "debug.h" @@ -49,4 +50,10 @@ void init_communication_interfaces( void ) DEBUG_PRINT( "init Control CAN - " ); init_can( g_control_can ); + + // Filter CAN messages - accept if (CAN_ID & mask) == (filter & mask) + g_control_can.init_Mask(0, 0, 0x7F0); // Filter for 0x0N0 to 0x0NF + g_control_can.init_Mask(1, 0, 0x7FF); // Don't use second filter + g_control_can.init_Filt(0, 0, OSCC_STEERING_CAN_ID_INDEX); + g_control_can.init_Filt(1, 0, OSCC_GLOBAL_CAN_ID_INDEX); } diff --git a/firmware/throttle/src/init.cpp b/firmware/throttle/src/init.cpp index f3091ee9..b8dd4439 100644 --- a/firmware/throttle/src/init.cpp +++ b/firmware/throttle/src/init.cpp @@ -6,6 +6,7 @@ #include +#include "can_protocols/global_can_protocol.h" #include "can_protocols/throttle_can_protocol.h" #include "communications.h" #include "debug.h" @@ -49,4 +50,10 @@ void init_communication_interfaces( void ) DEBUG_PRINT( "init Control CAN - " ); init_can( g_control_can ); + + // Filter CAN messages - accept if (CAN_ID & mask) == (filter & mask) + g_control_can.init_Mask(0, 0, 0x7F0); // Filter for 0x0N0 to 0x0NF + g_control_can.init_Mask(1, 0, 0x7FF); // Don't use second filter + g_control_can.init_Filt(0, 0, OSCC_THROTTLE_CAN_ID_INDEX); + g_control_can.init_Filt(1, 0, OSCC_GLOBAL_CAN_ID_INDEX); } From f87b8d3cb2b114f15e07b0a963de3a4b2e1dd7c9 Mon Sep 17 00:00:00 2001 From: Austin Morlan Date: Thu, 14 Dec 2017 16:03:49 -0800 Subject: [PATCH 43/84] Remove timeout tracking global variable --- firmware/brake/kia_soul_ev/include/globals.h | 2 -- firmware/brake/kia_soul_ev/src/brake_control.cpp | 2 -- firmware/brake/kia_soul_ev/src/communications.cpp | 2 -- firmware/brake/kia_soul_ev/src/init.cpp | 2 -- firmware/brake/kia_soul_ev/src/timers.cpp | 2 -- firmware/brake/kia_soul_petrol/include/globals.h | 2 -- firmware/brake/kia_soul_petrol/src/brake_control.cpp | 2 -- firmware/brake/kia_soul_petrol/src/communications.cpp | 2 -- firmware/brake/kia_soul_petrol/src/init.cpp | 2 -- firmware/brake/kia_soul_petrol/src/timers.cpp | 2 -- firmware/steering/include/globals.h | 2 -- firmware/steering/src/communications.cpp | 2 -- firmware/steering/src/init.cpp | 2 -- firmware/steering/src/steering_control.cpp | 2 -- firmware/steering/src/timers.cpp | 2 -- firmware/throttle/include/globals.h | 2 -- firmware/throttle/src/communications.cpp | 2 -- firmware/throttle/src/init.cpp | 2 -- firmware/throttle/src/throttle_control.cpp | 2 -- firmware/throttle/src/timers.cpp | 2 -- 20 files changed, 40 deletions(-) diff --git a/firmware/brake/kia_soul_ev/include/globals.h b/firmware/brake/kia_soul_ev/include/globals.h index 3b863e62..50391486 100644 --- a/firmware/brake/kia_soul_ev/include/globals.h +++ b/firmware/brake/kia_soul_ev/include/globals.h @@ -76,8 +76,6 @@ #endif -EXTERN volatile bool g_brake_command_timeout; - EXTERN volatile brake_control_state_s g_brake_control_state; diff --git a/firmware/brake/kia_soul_ev/src/brake_control.cpp b/firmware/brake/kia_soul_ev/src/brake_control.cpp index 0ea61035..883c057a 100644 --- a/firmware/brake/kia_soul_ev/src/brake_control.cpp +++ b/firmware/brake/kia_soul_ev/src/brake_control.cpp @@ -165,7 +165,6 @@ void enable_control( void ) digitalWrite( PIN_SPOOF_ENABLE, HIGH ); sei(); - g_brake_command_timeout = false; g_brake_control_state.enabled = true; DEBUG_PRINTLN( "Control enabled" ); @@ -188,7 +187,6 @@ void disable_control( void ) digitalWrite( PIN_SPOOF_ENABLE, LOW ); sei(); - g_brake_command_timeout = false; g_brake_control_state.enabled = false; DEBUG_PRINTLN( "Control disabled" ); diff --git a/firmware/brake/kia_soul_ev/src/communications.cpp b/firmware/brake/kia_soul_ev/src/communications.cpp index 974d4b7e..b0e58b62 100644 --- a/firmware/brake/kia_soul_ev/src/communications.cpp +++ b/firmware/brake/kia_soul_ev/src/communications.cpp @@ -117,8 +117,6 @@ static void process_brake_command( update_brake( brake_command->spoof_value_high, brake_command->spoof_value_low ); - - g_brake_command_timeout = false; } } diff --git a/firmware/brake/kia_soul_ev/src/init.cpp b/firmware/brake/kia_soul_ev/src/init.cpp index 39a0401e..b0bedb72 100644 --- a/firmware/brake/kia_soul_ev/src/init.cpp +++ b/firmware/brake/kia_soul_ev/src/init.cpp @@ -20,8 +20,6 @@ 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; } diff --git a/firmware/brake/kia_soul_ev/src/timers.cpp b/firmware/brake/kia_soul_ev/src/timers.cpp index 19fb21be..51dc4fb3 100644 --- a/firmware/brake/kia_soul_ev/src/timers.cpp +++ b/firmware/brake/kia_soul_ev/src/timers.cpp @@ -37,7 +37,5 @@ static void check_for_faults( void ) check_for_sensor_faults( ); - g_brake_command_timeout = true; - sei(); } diff --git a/firmware/brake/kia_soul_petrol/include/globals.h b/firmware/brake/kia_soul_petrol/include/globals.h index 281ea3e8..b475e0ce 100644 --- a/firmware/brake/kia_soul_petrol/include/globals.h +++ b/firmware/brake/kia_soul_petrol/include/globals.h @@ -142,8 +142,6 @@ #endif -EXTERN volatile bool g_brake_command_timeout; - EXTERN volatile brake_control_state_s g_brake_control_state; EXTERN pid_s g_pid; diff --git a/firmware/brake/kia_soul_petrol/src/brake_control.cpp b/firmware/brake/kia_soul_petrol/src/brake_control.cpp index 0779fd9f..a21df3c4 100644 --- a/firmware/brake/kia_soul_petrol/src/brake_control.cpp +++ b/firmware/brake/kia_soul_petrol/src/brake_control.cpp @@ -68,7 +68,6 @@ 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" ); @@ -92,7 +91,6 @@ 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" ); diff --git a/firmware/brake/kia_soul_petrol/src/communications.cpp b/firmware/brake/kia_soul_petrol/src/communications.cpp index c893e7a9..adcf5b12 100644 --- a/firmware/brake/kia_soul_petrol/src/communications.cpp +++ b/firmware/brake/kia_soul_petrol/src/communications.cpp @@ -117,8 +117,6 @@ static void process_brake_command( g_brake_control_state.commanded_pedal_position = brake_command->pedal_command; - - g_brake_command_timeout = false; } } diff --git a/firmware/brake/kia_soul_petrol/src/init.cpp b/firmware/brake/kia_soul_petrol/src/init.cpp index 20352326..34f6060a 100644 --- a/firmware/brake/kia_soul_petrol/src/init.cpp +++ b/firmware/brake/kia_soul_petrol/src/init.cpp @@ -26,8 +26,6 @@ void init_globals( void ) g_brake_control_state.operator_override = false; g_brake_control_state.dtcs = 0; - g_brake_command_timeout = false; - pid_zeroize( &g_pid, BRAKE_PID_WINDUP_GUARD ); g_pid.proportional_gain = BRAKE_PID_PROPORTIONAL_GAIN; g_pid.integral_gain = BRAKE_PID_INTEGRAL_GAIN; diff --git a/firmware/brake/kia_soul_petrol/src/timers.cpp b/firmware/brake/kia_soul_petrol/src/timers.cpp index 64f9928c..7a6d8b81 100644 --- a/firmware/brake/kia_soul_petrol/src/timers.cpp +++ b/firmware/brake/kia_soul_petrol/src/timers.cpp @@ -37,7 +37,5 @@ static void check_for_faults( void ) check_for_sensor_faults( ); - g_brake_command_timeout = true; - sei(); } diff --git a/firmware/steering/include/globals.h b/firmware/steering/include/globals.h index 04927c77..a70033d0 100644 --- a/firmware/steering/include/globals.h +++ b/firmware/steering/include/globals.h @@ -70,8 +70,6 @@ #endif -EXTERN volatile bool g_steering_command_timeout; - EXTERN volatile steering_control_state_s g_steering_control_state; diff --git a/firmware/steering/src/communications.cpp b/firmware/steering/src/communications.cpp index d889fa30..e593941a 100644 --- a/firmware/steering/src/communications.cpp +++ b/firmware/steering/src/communications.cpp @@ -117,8 +117,6 @@ static void process_steering_command( update_steering( steering_command->spoof_value_high, steering_command->spoof_value_low ); - - g_steering_command_timeout = false; } } diff --git a/firmware/steering/src/init.cpp b/firmware/steering/src/init.cpp index 500e0878..cb9fdbbf 100644 --- a/firmware/steering/src/init.cpp +++ b/firmware/steering/src/init.cpp @@ -20,8 +20,6 @@ void init_globals( void ) g_steering_control_state.enabled = false; g_steering_control_state.operator_override = false; g_steering_control_state.dtcs = 0; - - g_steering_command_timeout = false; } diff --git a/firmware/steering/src/steering_control.cpp b/firmware/steering/src/steering_control.cpp index 8690fce6..27dacc63 100644 --- a/firmware/steering/src/steering_control.cpp +++ b/firmware/steering/src/steering_control.cpp @@ -171,7 +171,6 @@ 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" ); @@ -194,7 +193,6 @@ void disable_control( void ) digitalWrite( PIN_SPOOF_ENABLE, LOW ); sei(); - g_steering_command_timeout = false; g_steering_control_state.enabled = false; filtered_diff = 0; diff --git a/firmware/steering/src/timers.cpp b/firmware/steering/src/timers.cpp index d627bbd8..67207759 100644 --- a/firmware/steering/src/timers.cpp +++ b/firmware/steering/src/timers.cpp @@ -37,7 +37,5 @@ static void check_for_faults( void ) check_for_sensor_faults( ); - g_steering_command_timeout = true; - sei(); } diff --git a/firmware/throttle/include/globals.h b/firmware/throttle/include/globals.h index 1109a35c..6ce7d511 100644 --- a/firmware/throttle/include/globals.h +++ b/firmware/throttle/include/globals.h @@ -70,8 +70,6 @@ #endif -EXTERN volatile bool g_throttle_command_timeout; - EXTERN volatile throttle_control_state_s g_throttle_control_state; diff --git a/firmware/throttle/src/communications.cpp b/firmware/throttle/src/communications.cpp index 4c65810d..c9ad13da 100644 --- a/firmware/throttle/src/communications.cpp +++ b/firmware/throttle/src/communications.cpp @@ -117,8 +117,6 @@ static void process_throttle_command( update_throttle( throttle_command->spoof_value_high, throttle_command->spoof_value_low ); - - g_throttle_command_timeout = false; } } diff --git a/firmware/throttle/src/init.cpp b/firmware/throttle/src/init.cpp index f3091ee9..b24855cf 100644 --- a/firmware/throttle/src/init.cpp +++ b/firmware/throttle/src/init.cpp @@ -20,8 +20,6 @@ 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_command_timeout = false; } diff --git a/firmware/throttle/src/throttle_control.cpp b/firmware/throttle/src/throttle_control.cpp index 414543f8..9a77224c 100644 --- a/firmware/throttle/src/throttle_control.cpp +++ b/firmware/throttle/src/throttle_control.cpp @@ -151,7 +151,6 @@ 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" ); @@ -174,7 +173,6 @@ 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 daeea326..4c90918b 100644 --- a/firmware/throttle/src/timers.cpp +++ b/firmware/throttle/src/timers.cpp @@ -37,7 +37,5 @@ static void check_for_faults( void ) check_for_sensor_faults( ); - g_throttle_command_timeout = true; - sei(); } From a33135995024c82d81d0a3fc92552856ac90b2a7 Mon Sep 17 00:00:00 2001 From: Austin Morlan Date: Thu, 14 Dec 2017 16:23:56 -0800 Subject: [PATCH 44/84] Remove extra communications.cpp file --- firmware/throttle/src/communications.1.cpp | 222 --------------------- 1 file changed, 222 deletions(-) delete mode 100644 firmware/throttle/src/communications.1.cpp diff --git a/firmware/throttle/src/communications.1.cpp b/firmware/throttle/src/communications.1.cpp deleted file mode 100644 index af44c386..00000000 --- a/firmware/throttle/src/communications.1.cpp +++ /dev/null @@ -1,222 +0,0 @@ -/** - * @file communications.cpp - * - */ - - -#include - -#include "can_protocols/global_can_protocol.h" -#include "can_protocols/throttle_can_protocol.h" -#include "communications.h" -#include "debug.h" -#include "globals.h" -#include "mcp_can.h" -#include "oscc_can.h" -// #include "oscc_eeprom.h" -#include "throttle_control.h" - - -static void process_rx_frame( - const can_frame_s * const frame ); - -static void process_throttle_command( - const uint8_t * const data ); - -static void process_fault_report( - const uint8_t * const data ); - -static void process_config_u16( - const uint8_t * const data ); - -static void process_config_f32( - const uint8_t * const data ); - - -void publish_throttle_report( void ) -{ - oscc_throttle_report_s throttle_report; - - throttle_report.magic[0] = (uint8_t) OSCC_MAGIC_BYTE_0; - throttle_report.magic[1] = (uint8_t) OSCC_MAGIC_BYTE_1; - throttle_report.enabled = (uint8_t) g_throttle_control_state.enabled; - throttle_report.operator_override = (uint8_t) g_throttle_control_state.operator_override; - throttle_report.dtcs = g_throttle_control_state.dtcs; - - cli(); - g_control_can.sendMsgBuf( - OSCC_THROTTLE_REPORT_CAN_ID, - CAN_STANDARD, - OSCC_THROTTLE_REPORT_CAN_DLC, - (uint8_t*) &throttle_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_THROTTLE; - fault_report.dtcs = g_throttle_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_throttle_control_state.enabled == true ) - { - if( g_throttle_command_timeout == true ) - { - disable_control( ); - - publish_fault_report( ); - - DEBUG_PRINTLN( "Timeout - 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 ) - { - Serial.println(frame->id, 16); - - // if( (frame->data[0] == OSCC_MAGIC_BYTE_0) - // && (frame->data[1] == OSCC_MAGIC_BYTE_1) ) - // { - // 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 ); - // } - // else if ( frame->id == OSCC_FAULT_REPORT_CAN_ID ) - // { - // process_fault_report( frame-> data ); - // } - // else if ( frame->id == OSCC_CONFIG_F32_CAN_ID ) - // { - // process_config_f32( frame->data ); - // } - // else if ( frame->id == OSCC_CONFIG_U16_CAN_ID ) - // { - // process_config_u16( frame->data ); - // } - // } - } -} - - -static void process_throttle_command( - const uint8_t * const data ) -{ - if ( data != NULL ) - { - const oscc_throttle_command_s * const throttle_command = - (oscc_throttle_command_s *) data; - - update_throttle( - throttle_command->spoof_value_high, - throttle_command->spoof_value_low ); - - g_throttle_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 ); - } -} - - -static void process_config_u16( - const uint8_t * const data ) -{ - // if ( data != NULL ) - // { - // const oscc_config_u16_s * const config = - // (oscc_config_u16_s *) data; - - // if ( (config->name == OSCC_CONFIG_U16_THROTTLE_PEDAL_OVERRIDE_THRESHOLD) - // || (config->name == OSCC_CONFIG_U16_THROTTLE_FAULT_CHECK_FREQUENCY_IN_HZ) ) - // { - // Serial.print("n "); - // Serial.print(config->name); - // Serial.print(";v "); - // Serial.println(config->value); - // oscc_eeprom_write_u16( config->name, config->value ); - - // uint16_t val = oscc_eeprom_read_u16( config->name ); - - // Serial.println(val); - // } - // } -} - - -static void process_config_f32( - const uint8_t * const data ) -{ - // if ( data != NULL ) - // { - // const oscc_config_f32_s * const config = - // (oscc_config_f32_s *) data; - - // if ( (config->name == OSCC_CONFIG_F32_THROTTLE_SPOOF_LOW_SIGNAL_VOLTAGE_MIN) - // || (config->name == OSCC_CONFIG_F32_THROTTLE_SPOOF_LOW_SIGNAL_VOLTAGE_MAX) - // || (config->name == OSCC_CONFIG_F32_THROTTLE_SPOOF_HIGH_SIGNAL_VOLTAGE_MIN) - // || (config->name == OSCC_CONFIG_F32_THROTTLE_SPOOF_HIGH_SIGNAL_VOLTAGE_MAX) ) - // { - // oscc_eeprom_write_f32( config->name, config->value ); - - // float val = oscc_eeprom_read_f32( config->name ); - - // Serial.println(val); - // } - // } -} From e3d273349aab353e7056b650edce92a0190478dd Mon Sep 17 00:00:00 2001 From: Katie Cleary Date: Thu, 14 Dec 2017 17:34:20 -0800 Subject: [PATCH 45/84] Add environment variables to Jenkinsfile --- Jenkinsfile | 14 +++++++++----- 1 file changed, 9 insertions(+), 5 deletions(-) diff --git a/Jenkinsfile b/Jenkinsfile index 4e566ff0..265ffe2a 100644 --- a/Jenkinsfile +++ b/Jenkinsfile @@ -22,8 +22,10 @@ node('arduino') { 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!' + withEnv(["PATH+CARGO=$HOME/.cargo/bin"]) { + 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!' } @@ -32,8 +34,10 @@ node('arduino') { 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!' + withEnv(["PATH+CARGO=$HOME/.cargo/bin"]) { + 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!' } @@ -44,4 +48,4 @@ node('arduino') { finally { deleteDir() } -} +} \ No newline at end of file From df2649b5024ac9c90ff793ff177cfd32edf46e43 Mon Sep 17 00:00:00 2001 From: Katie Cleary Date: Thu, 14 Dec 2017 17:42:50 -0800 Subject: [PATCH 46/84] Testing rustup path --- Jenkinsfile | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/Jenkinsfile b/Jenkinsfile index 265ffe2a..34637c0c 100644 --- a/Jenkinsfile +++ b/Jenkinsfile @@ -22,8 +22,9 @@ node('arduino') { 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 'which rustup' withEnv(["PATH+CARGO=$HOME/.cargo/bin"]) { - 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' + sh 'which rustup && 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!' } } From 78165995debff678e13c84e4be728f3b77ccb00e Mon Sep 17 00:00:00 2001 From: Katie Cleary Date: Thu, 14 Dec 2017 17:44:18 -0800 Subject: [PATCH 47/84] Jenkins vs. CMake rustup --- Jenkinsfile | 1 - firmware/throttle/tests/CMakeLists.txt | 2 +- 2 files changed, 1 insertion(+), 2 deletions(-) diff --git a/Jenkinsfile b/Jenkinsfile index 34637c0c..629d6979 100644 --- a/Jenkinsfile +++ b/Jenkinsfile @@ -22,7 +22,6 @@ node('arduino') { 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 'which rustup' withEnv(["PATH+CARGO=$HOME/.cargo/bin"]) { sh 'which rustup && 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!' diff --git a/firmware/throttle/tests/CMakeLists.txt b/firmware/throttle/tests/CMakeLists.txt index 71820f71..e1c3077f 100644 --- a/firmware/throttle/tests/CMakeLists.txt +++ b/firmware/throttle/tests/CMakeLists.txt @@ -56,5 +56,5 @@ add_custom_target( add_custom_target( run-throttle-property-tests COMMAND - cargo test -- --test-threads=1 + which rustup && cargo test -- --test-threads=1 WORKING_DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR}/property) From 7f58d94686ce141b713fade02be18d7668d8468e Mon Sep 17 00:00:00 2001 From: Katie Cleary Date: Thu, 14 Dec 2017 18:02:41 -0800 Subject: [PATCH 48/84] Cleanup --- Jenkinsfile | 2 +- firmware/throttle/tests/CMakeLists.txt | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Jenkinsfile b/Jenkinsfile index 629d6979..265ffe2a 100644 --- a/Jenkinsfile +++ b/Jenkinsfile @@ -23,7 +23,7 @@ node('arduino') { echo 'Kia Soul Petrol Unit Tests Complete!' }, 'kia soul petrol property-based tests': { withEnv(["PATH+CARGO=$HOME/.cargo/bin"]) { - sh 'which rustup && 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' + 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!' } } diff --git a/firmware/throttle/tests/CMakeLists.txt b/firmware/throttle/tests/CMakeLists.txt index e1c3077f..71820f71 100644 --- a/firmware/throttle/tests/CMakeLists.txt +++ b/firmware/throttle/tests/CMakeLists.txt @@ -56,5 +56,5 @@ add_custom_target( add_custom_target( run-throttle-property-tests COMMAND - which rustup && cargo test -- --test-threads=1 + cargo test -- --test-threads=1 WORKING_DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR}/property) From 6dcc4fd55ab80304cd532e0c75ad119d769f7714 Mon Sep 17 00:00:00 2001 From: Katie Cleary Date: Thu, 14 Dec 2017 18:08:03 -0800 Subject: [PATCH 49/84] Attempt to lock version --- Jenkinsfile | 4 ++-- firmware/brake/kia_soul_ev/tests/CMakeLists.txt | 2 +- firmware/brake/kia_soul_petrol/tests/CMakeLists.txt | 2 +- firmware/steering/tests/CMakeLists.txt | 2 +- firmware/throttle/tests/CMakeLists.txt | 2 +- 5 files changed, 6 insertions(+), 6 deletions(-) diff --git a/Jenkinsfile b/Jenkinsfile index 265ffe2a..91871d71 100644 --- a/Jenkinsfile +++ b/Jenkinsfile @@ -23,7 +23,7 @@ node('arduino') { echo 'Kia Soul Petrol Unit Tests Complete!' }, 'kia soul petrol property-based tests': { withEnv(["PATH+CARGO=$HOME/.cargo/bin"]) { - 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' + sh 'rustup self update && rustup update && rustup install 1.20.0 && rustup component add rust-src && 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!' } } @@ -35,7 +35,7 @@ node('arduino') { echo 'Kia Soul EV Unit Tests Complete!' }, 'kia soul ev property-based tests': { withEnv(["PATH+CARGO=$HOME/.cargo/bin"]) { - 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' + sh 'rustup self update && rustup update && rustup install 1.20.0 && rustup component add rust-src && 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!' } } diff --git a/firmware/brake/kia_soul_ev/tests/CMakeLists.txt b/firmware/brake/kia_soul_ev/tests/CMakeLists.txt index 900e260e..5138d5ff 100644 --- a/firmware/brake/kia_soul_ev/tests/CMakeLists.txt +++ b/firmware/brake/kia_soul_ev/tests/CMakeLists.txt @@ -56,5 +56,5 @@ add_custom_target( add_custom_target( run-brake-property-tests COMMAND - cargo test -- --test-threads=1 + cargo +1.20.0 test -- --test-threads=1 WORKING_DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR}/property) diff --git a/firmware/brake/kia_soul_petrol/tests/CMakeLists.txt b/firmware/brake/kia_soul_petrol/tests/CMakeLists.txt index 8a25a99d..a65710c0 100644 --- a/firmware/brake/kia_soul_petrol/tests/CMakeLists.txt +++ b/firmware/brake/kia_soul_petrol/tests/CMakeLists.txt @@ -59,5 +59,5 @@ add_custom_target( add_custom_target( run-brake-property-tests COMMAND - cargo test -- --test-threads=1 + cargo +1.20.0 test -- --test-threads=1 WORKING_DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR}/property) diff --git a/firmware/steering/tests/CMakeLists.txt b/firmware/steering/tests/CMakeLists.txt index c88d601d..33600d56 100644 --- a/firmware/steering/tests/CMakeLists.txt +++ b/firmware/steering/tests/CMakeLists.txt @@ -59,5 +59,5 @@ add_custom_target( add_custom_target( run-steering-property-tests COMMAND - cargo test -- --test-threads=1 + cargo +1.20.0 test -- --test-threads=1 WORKING_DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR}/property) diff --git a/firmware/throttle/tests/CMakeLists.txt b/firmware/throttle/tests/CMakeLists.txt index 71820f71..5c868542 100644 --- a/firmware/throttle/tests/CMakeLists.txt +++ b/firmware/throttle/tests/CMakeLists.txt @@ -56,5 +56,5 @@ add_custom_target( add_custom_target( run-throttle-property-tests COMMAND - cargo test -- --test-threads=1 + cargo +1.20.0 test -- --test-threads=1 WORKING_DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR}/property) From 7d665bafc11219b2641ccd77481bae0ab7edbae3 Mon Sep 17 00:00:00 2001 From: Austin Morlan Date: Fri, 15 Dec 2017 10:14:03 -0800 Subject: [PATCH 50/84] Fix for style guide --- firmware/brake/kia_soul_ev/src/init.cpp | 8 ++++---- firmware/brake/kia_soul_petrol/src/init.cpp | 8 ++++---- firmware/steering/src/init.cpp | 8 ++++---- firmware/throttle/src/init.cpp | 8 ++++---- 4 files changed, 16 insertions(+), 16 deletions(-) diff --git a/firmware/brake/kia_soul_ev/src/init.cpp b/firmware/brake/kia_soul_ev/src/init.cpp index 6b5bab9c..34528f0f 100644 --- a/firmware/brake/kia_soul_ev/src/init.cpp +++ b/firmware/brake/kia_soul_ev/src/init.cpp @@ -54,8 +54,8 @@ void init_communication_interfaces( void ) init_can( g_control_can ); // Filter CAN messages - accept if (CAN_ID & mask) == (filter & mask) - g_control_can.init_Mask(0, 0, 0x7F0); // Filter for 0x0N0 to 0x0NF - g_control_can.init_Mask(1, 0, 0x7FF); // Don't use second filter - g_control_can.init_Filt(0, 0, OSCC_BRAKE_CAN_ID_INDEX); - g_control_can.init_Filt(1, 0, OSCC_GLOBAL_CAN_ID_INDEX); + g_control_can.init_Mask( 0, 0, 0x7F0 ); // Filter for 0x0N0 to 0x0NF + g_control_can.init_Mask( 1, 0, 0x7FF ); // Don't use second filter + g_control_can.init_Filt( 0, 0, OSCC_BRAKE_CAN_ID_INDEX ); + g_control_can.init_Filt( 1, 0, OSCC_GLOBAL_CAN_ID_INDEX ); } diff --git a/firmware/brake/kia_soul_petrol/src/init.cpp b/firmware/brake/kia_soul_petrol/src/init.cpp index e033a12d..c8e2db9c 100644 --- a/firmware/brake/kia_soul_petrol/src/init.cpp +++ b/firmware/brake/kia_soul_petrol/src/init.cpp @@ -64,8 +64,8 @@ void init_communication_interfaces( void ) init_can( g_control_can ); // Filter CAN messages - accept if (CAN_ID & mask) == (filter & mask) - g_control_can.init_Mask(0, 0, 0x7F0); // Filter for 0x0N0 to 0x0NF - g_control_can.init_Mask(1, 0, 0x7FF); // Don't use second filter - g_control_can.init_Filt(0, 0, OSCC_BRAKE_CAN_ID_INDEX); - g_control_can.init_Filt(1, 0, OSCC_GLOBAL_CAN_ID_INDEX); + g_control_can.init_Mask( 0, 0, 0x7F0 ); // Filter for 0x0N0 to 0x0NF + g_control_can.init_Mask( 1, 0, 0x7FF ); // Don't use second filter + g_control_can.init_Filt( 0, 0, OSCC_BRAKE_CAN_ID_INDEX ); + g_control_can.init_Filt( 1, 0, OSCC_GLOBAL_CAN_ID_INDEX ); } diff --git a/firmware/steering/src/init.cpp b/firmware/steering/src/init.cpp index e2271f55..780acea7 100644 --- a/firmware/steering/src/init.cpp +++ b/firmware/steering/src/init.cpp @@ -52,8 +52,8 @@ void init_communication_interfaces( void ) init_can( g_control_can ); // Filter CAN messages - accept if (CAN_ID & mask) == (filter & mask) - g_control_can.init_Mask(0, 0, 0x7F0); // Filter for 0x0N0 to 0x0NF - g_control_can.init_Mask(1, 0, 0x7FF); // Don't use second filter - g_control_can.init_Filt(0, 0, OSCC_STEERING_CAN_ID_INDEX); - g_control_can.init_Filt(1, 0, OSCC_GLOBAL_CAN_ID_INDEX); + g_control_can.init_Mask( 0, 0, 0x7F0 ); // Filter for 0x0N0 to 0x0NF + g_control_can.init_Mask( 1, 0, 0x7FF ); // Don't use second filter + g_control_can.init_Filt( 0, 0, OSCC_STEERING_CAN_ID_INDEX ); + g_control_can.init_Filt( 1, 0, OSCC_GLOBAL_CAN_ID_INDEX ); } diff --git a/firmware/throttle/src/init.cpp b/firmware/throttle/src/init.cpp index b8dd4439..5fcc4059 100644 --- a/firmware/throttle/src/init.cpp +++ b/firmware/throttle/src/init.cpp @@ -52,8 +52,8 @@ void init_communication_interfaces( void ) init_can( g_control_can ); // Filter CAN messages - accept if (CAN_ID & mask) == (filter & mask) - g_control_can.init_Mask(0, 0, 0x7F0); // Filter for 0x0N0 to 0x0NF - g_control_can.init_Mask(1, 0, 0x7FF); // Don't use second filter - g_control_can.init_Filt(0, 0, OSCC_THROTTLE_CAN_ID_INDEX); - g_control_can.init_Filt(1, 0, OSCC_GLOBAL_CAN_ID_INDEX); + g_control_can.init_Mask( 0, 0, 0x7F0 ); // Filter for 0x0N0 to 0x0NF + g_control_can.init_Mask( 1, 0, 0x7FF ); // Don't use second filter + g_control_can.init_Filt( 0, 0, OSCC_THROTTLE_CAN_ID_INDEX ); + g_control_can.init_Filt( 1, 0, OSCC_GLOBAL_CAN_ID_INDEX ); } From 0cf186297a821b931f51e4ebd95abd93c0dba005 Mon Sep 17 00:00:00 2001 From: Austin Morlan Date: Fri, 15 Dec 2017 12:01:25 -0800 Subject: [PATCH 51/84] Update oscc.h with global CAN protocol file --- api/include/oscc.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/api/include/oscc.h b/api/include/oscc.h index 39c06314..2202a071 100644 --- a/api/include/oscc.h +++ b/api/include/oscc.h @@ -12,7 +12,7 @@ #include #include "can_protocols/brake_can_protocol.h" -#include "can_protocols/fault_can_protocol.h" +#include "can_protocols/global_can_protocol.h" #include "can_protocols/steering_can_protocol.h" #include "can_protocols/throttle_can_protocol.h" #include "vehicles.h" From 3ed64009608db7c0f3c6bfa302a196e855cee049 Mon Sep 17 00:00:00 2001 From: Shea Newton Date: Wed, 3 Jan 2018 10:57:19 -0800 Subject: [PATCH 52/84] Incorporate a template for raising issues. Prior to this commit, when raising a new issue users are presented with a blank canvas. This leads to inconsitent reports from users as well the requirement for the maintainers to poll for information that we generally always need up front. As a solution, Github facilitates templating the default issue dialogue. This PR represents an attempt at templating the issue dialogue so that users are prompted to provide information that would be helpful to the maintainers from the outset. For an example of another project that employs a helpful issue template, see [rust-bindgen](https://github.com/rust-lang-nursery/rust-bindgen/issues). Click the green "New Issue" button to see a great template in action. --- .github/ISSUE_TEMPLATE.md | 56 +++++++++++++++++++++++++++++++++++++++ 1 file changed, 56 insertions(+) create mode 100644 .github/ISSUE_TEMPLATE.md diff --git a/.github/ISSUE_TEMPLATE.md b/.github/ISSUE_TEMPLATE.md new file mode 100644 index 00000000..4c5a3e55 --- /dev/null +++ b/.github/ISSUE_TEMPLATE.md @@ -0,0 +1,56 @@ + + + + + + + + +### Proposed feature + + +### Use case + + + + + + +### Expected Information + + +### Available Documentation + + + + + + +### Expected behavior + + +### Actual behavior + + +### Steps to reproduce + + +### Version info +_What's the output of running `git describe --tags` in your OSCC directory?_ + + +### Hardware info + + + + + From 444dc8146958238d76c6809e78811c60b42f13e0 Mon Sep 17 00:00:00 2001 From: Shea Newton Date: Wed, 3 Jan 2018 13:32:32 -0800 Subject: [PATCH 53/84] Address changes requested. This commit represents changes to address those reqested. Each potential issue's template has been clearly marked as so. Wording and spelling/grammar mistakes have been fixed. Overall this commit is an attempt to make the template more readable, intuitive and generally useful (rather than just adding an extra layer of confusion.) --- .github/ISSUE_TEMPLATE.md | 68 +++++++++++++++++++++++---------------- 1 file changed, 41 insertions(+), 27 deletions(-) diff --git a/.github/ISSUE_TEMPLATE.md b/.github/ISSUE_TEMPLATE.md index 4c5a3e55..0267d0d5 100644 --- a/.github/ISSUE_TEMPLATE.md +++ b/.github/ISSUE_TEMPLATE.md @@ -1,4 +1,10 @@ - + @@ -6,51 +12,59 @@ Shoot an email to drivekit@polysync.io --> +Technical issue template. -### Proposed feature - - -### Use case - +Are you having a technical issue? Fill in the following blocks to help us +tackle it! +--> +### Expected behavior + +### Actual behavior + - +### Steps to reproduce + -### Expected Information - +### Version info +_What's the output of running `git describe --tags` in your OSCC directory?_ -### Available Documentation - +### Hardware info + -### Expected behavior - +### Proposed feature or changes + -### Actual behavior - +### Use case + -### Steps to reproduce - -### Version info -_What's the output of running `git describe --tags` in your OSCC directory?_ + +Have you found a bug in documentation or wish something was documented that +isn't? Fill in the following blocks to help us help you! +--> + +### Documentation expected + +### Documentation available + From 4a2027f92222fe18e4fca287d09235b829978e1d Mon Sep 17 00:00:00 2001 From: Katie Cleary Date: Thu, 4 Jan 2018 16:00:16 -0800 Subject: [PATCH 54/84] Remove toolchain updating from Jenkinsfile --- Jenkinsfile | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Jenkinsfile b/Jenkinsfile index 91871d71..265ffe2a 100644 --- a/Jenkinsfile +++ b/Jenkinsfile @@ -23,7 +23,7 @@ node('arduino') { echo 'Kia Soul Petrol Unit Tests Complete!' }, 'kia soul petrol property-based tests': { withEnv(["PATH+CARGO=$HOME/.cargo/bin"]) { - sh 'rustup self update && rustup update && rustup install 1.20.0 && rustup component add rust-src && 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' + 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!' } } @@ -35,7 +35,7 @@ node('arduino') { echo 'Kia Soul EV Unit Tests Complete!' }, 'kia soul ev property-based tests': { withEnv(["PATH+CARGO=$HOME/.cargo/bin"]) { - sh 'rustup self update && rustup update && rustup install 1.20.0 && rustup component add rust-src && 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' + 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!' } } From 22a672e6606c1adc195487da179d715466f0f613 Mon Sep 17 00:00:00 2001 From: Shea Newton Date: Thu, 4 Jan 2018 16:04:29 -0800 Subject: [PATCH 55/84] Add getting started resources to API. Prior to this commit there was no real indication of how to incorporate the API into your own project or a step by step for a complete example without digging into an external repository like the joystick commander. This PR represents an attempt to make the OSCC API self-explanatory so that a new user is able to get up and running without needing to go anywhere else. Becasuse I'm new to the REPO and the functionality I expect change requests on this PR to help fill in the docs. I'd appreciate reviewers providing specific sentences for me to work with in those requests. After this commit, the intention is that a new user can visit the OSCC `api` directory and have the resources they need to start their own project that incorporates the API. Thanks for taking a look! --- api/CMakeLists.txt | 27 ++++++ api/README.md | 218 +++++++++++++++++++++++++++++++++++++++++++++ 2 files changed, 245 insertions(+) create mode 100644 api/CMakeLists.txt create mode 100644 api/README.md diff --git a/api/CMakeLists.txt b/api/CMakeLists.txt new file mode 100644 index 00000000..17de9626 --- /dev/null +++ b/api/CMakeLists.txt @@ -0,0 +1,27 @@ +cmake_minimum_required(VERSION 2.8) + +project(osccapi) + +include(${CMAKE_SOURCE_DIR}/OsccConfig.cmake) + +set(INCLUDES ${CMAKE_SOURCE_DIR}/include ${CMAKE_SOURCE_DIR}/src) +set(SOURCES ${CMAKE_SOURCE_DIR}/src/oscc.c) +set_source_files_properties(SOURCES PROPERTIES LANGUAGE C) + +set(OBJECTS ${PROJECT_NAME}_objects) +set(SHARED_LIB ${PROJECT_NAME}_shared_lib) +set(STATIC_LIB ${PROJECT_NAME}_static_lib) + +# Reuse object files for both shared and static libraries +# rather than recompiling for both +add_library(${OBJECTS} OBJECT ${SOURCES}) +target_include_directories(${OBJECTS} PUBLIC ${INCLUDES}) +set_target_properties(${OBJECTS} PROPERTIES POSITION_INDEPENDENT_CODE 1) + +add_library(${SHARED_LIB} SHARED $) +set_target_properties(${SHARED_LIB} PROPERTIES OUTPUT_NAME ${PROJECT_NAME}) +target_include_directories(${SHARED_LIB} PUBLIC ${INCLUDES}) + +add_library(${STATIC_LIB} STATIC $) +target_include_directories(${STATIC_LIB} PUBLIC ${INCLUDES}) +set_target_properties(${STATIC_LIB} PROPERTIES OUTPUT_NAME ${PROJECT_NAME}) \ No newline at end of file diff --git a/api/README.md b/api/README.md new file mode 100644 index 00000000..4d4c9d19 --- /dev/null +++ b/api/README.md @@ -0,0 +1,218 @@ + +# Getting started with the OSCC API + +There are a few options on how to get started with your own application that +uses the OSCC API. + +## The library approach + +To build both `libosccapi.so` and `libosccapi.a` for the Kia Soul EV, +you can run the following commands on Linux from this directory. +``` +mkdir build && cd build +cmake -DKIA_SOUL_EV=ON .. +make +``` +Substitute `-DKIA_SOUL_EV` for another supported vehicle if the EV isn't your +target. For example `-DKIA_SOUL=ON` will build the libraries with support +for the Kia Soul Petrol instead. + +### Using `libosccapi.so` +Using the shared library for a project that uses the OSCC API is easy! +The following is an example `CMakeLists.txt` for doing just that. This example +is all you need for a projec with it's own source file, `main.c`. +``` +cmake_minimum_required(VERSION 2.8) +project(an_example) +set(OSCC_API_INSTALL /path_to/oscc_directory/api) +link_directories(${OSCC_API_INSTALL}/build) +set(OSCC_INCLUDES ${OSCC_API_INSTALL}/include) +set(SOURCES ${CMAKE_SOURCE_DIR}/src/main.c) +add_executable(${PROJECT_NAME} ${SOURCES}) +target_include_directories(${PROJECT_NAME} PUBLIC ${OSCC_INCLUDES}) +target_link_libraries(${PROJECT_NAME} PUBLIC osccapi) +``` + +### Using `libosccapi.a` +Using the static library isn't much different than the shared one, +the CMakeLists.txt just requires the full path to the library as it doesn't +intuit it from a provided link_directory. +``` +cmake_minimum_required(VERSION 2.8) +project(an_example) +set(OSCC_API_INSTALL /path_to/oscc_directory/api) +set(OSCC_INCLUDES ${OSCC_API_INSTALL}/include) +set(SOURCES ${CMAKE_SOURCE_DIR}/src/main.c) +add_executable(${PROJECT_NAME} ${SOURCES}) +target_include_directories(${PROJECT_NAME} PUBLIC ${OSCC_INCLUDES}) +target_link_libraries(${PROJECT_NAME} PUBLIC ${OSCC_API_INSTALL}/build/libosccapi.a) +``` + +## Straight from the sources +Another approach is to just include the OSCC API source code in your project. +Since the OSCC API has no dependencies beyond a Linux system, this is easy too! +Here's an example CMakeLists.txt that takes the straight from the sources +approach. Note that it makes the assumption that we're building for the Kia +Soul Petrol with the `"-DKIA_SOUL=ON"`. + +``` +cmake_minimum_required(VERSION 2.8) +project(an_example) +set(OSCC_API_INSTALL /path_to/oscc_directory/api) +set(OSCC_INCLUDES ${OSCC_API_INSTALL}/include ${OSCC_API_INSTALL}/src) +set(SOURCES ${CMAKE_SOURCE_DIR}/src/main.c ${OSCC_API_INSTALL}/src/oscc.c) +add_executable(${PROJECT_NAME} ${SOURCES}) +target_compile_definitions(${PROJECT_NAME} PUBLIC "-DKIA_SOUL=ON") +target_include_directories(${PROJECT_NAME} PUBLIC ${OSCC_INCLUDES}) +``` + +## Using the API + +Let's walk through actually writing some code that uses the OSCC API, an example +program the listens to all the information that OSCC reports. Feel free to +experiment with this code, if it's all put into a `main.c` you can use +any of the CMakeLists.txt options above to build it. + +First, we'll do some generic setup. This isn't a requriement of the OSCC API +but might make our example a little more useful. + +``` +#include // printf +#include // SIGINT +#include // usleep +``` +Okay, now for the actual OSCC API include that allows us to initiate, +listen to each message type and then properly release OSCC. `oscc.h` is +all you need! + +``` +#include "oscc.h" // oscc_open, oscc_disable, oscc_close and each subscribe. +``` +In order for our example to trigger the proper cleanup when we press `Ctrl+C` +to quit the program, we'll setup a signal handler to let us know. + +``` +// Global indication of Ctrl+C. +static int EXIT_SIGNALED = OSCC_OK; + +// Help exiting gracefully. +void signal_handler(int signal_number) +{ + if (signal_number == SIGINT) + { + EXIT_SIGNALED = OSCC_ERROR; + } +} +``` + +Now lets walk through our OSCC message subscribers. When we get a report from +something OSCC provides, let's print a message reporting what we see. + +__Throttle__ +``` +void throttle_callback(oscc_throttle_report_s * report) +{ + printf("Hello from throttle_callback!\n"); +} +``` +__Steering__ +``` +void steering_callback(oscc_steering_report_s * report) +{ + printf("steering_callback reporting!\n"); +} +``` +__Brake__ +``` +void brake_callback(oscc_brake_report_s * report) +{ + printf("'Brake-ing' news from the brake_callback!\n"); +} +``` +__Fault__ +``` +void fault_callback(oscc_fault_report_s * report) +{ + printf("Oh! Something caused a fault and we made it to the fault_callback. We're seeing a "); + + if (report->fault_origin_id == FAULT_ORIGIN_BRAKE) + { + printf("brake fault!\n"); + } + else if (report->fault_origin_id == FAULT_ORIGIN_STEERING) + { + printf("steering fault!\n"); + } + else if (report->fault_origin_id == FAULT_ORIGIN_THROTTLE) + { + printf("throttle fault!\n"); + } +} +``` +__OBD__ +``` +static void obd_callback(struct can_frame * frame) +{ + printf("From the obd_callback, CAN ID: %u\n", frame->can_id); +} +``` +Okay, we're all setup! Let get to work! Out code base it pretty small so +we'll just stick to the `main` function +``` +int main +{ +``` +Now let's put that 'Ctrl+C' setup we did earlier to use. +``` + struct sigaction sig; + sig.sa_handler = signal_handler; + sigaction(SIGINT, &sig, NULL); +``` +Next we need to tell OSCC where to to send it's messages. +``` + oscc_subscribe_to_obd_messages(obd_callback); + oscc_subscribe_to_brake_reports(brake_callback); + oscc_subscribe_to_steering_reports(steering_callback); + oscc_subscribe_to_throttle_reports(throttle_callback); + oscc_subscribe_to_fault_reports(fault_callback); +``` +In order to verify that initalizing OSCC succeeds and clean things up +if we fail, we need a way to capture results. +``` + oscc_result_t return_value; +``` +For brevity, we'll assume that we're opening CAN channel 0 to connect to OSCC +and spin it up! +``` + int channel = 0; + return_value = oscc_open(channel); +``` +Since we captured the result of out call to oscc_open, we can verify it +succeded before moving on or signal that we need to clean things up. +``` + if(return_value != OSCC_OK) + { + printf("Error in oscc_open!\n"); + EXIT_SIGNALED = OSCC_ERROR; + } +``` + +Now we wait, just let the callbacks to their work. To avoid loading the +CPU with this example, we'll sleep for a bit (50ms) on each iteration. +``` + while(EXIT_SIGNALED == OSCC_OK) + { + (void) usleep(50000); + } +``` + +Once we're through, we can clean things up. +``` + oscc_disable(); + oscc_close(channel); +``` + +Don't forget to close up the `main` function! +``` +} +``` \ No newline at end of file From 8c2545276e1c83a9102b4430ccdc796d1b7b3a9e Mon Sep 17 00:00:00 2001 From: Robert Brown Date: Fri, 5 Jan 2018 16:22:36 -0800 Subject: [PATCH 56/84] Remove timer and combine override with fault Prior to this commit the firmware would cause a roughtly 1000ms blip at the frequency of the timers for fault detection. This commit moves the fault detection into the main loop and combines the override into the fault detection so that only one read to the DAC occurs. --- firmware/brake/kia_soul_ev/CMakeLists.txt | 5 +- .../brake/kia_soul_ev/include/brake_control.h | 20 +---- firmware/brake/kia_soul_ev/include/timers.h | 25 ------ .../brake/kia_soul_ev/src/brake_control.cpp | 74 ++++----------- firmware/brake/kia_soul_ev/src/main.cpp | 7 +- firmware/brake/kia_soul_ev/src/timers.cpp | 41 --------- firmware/steering/CMakeLists.txt | 5 +- firmware/steering/include/steering_control.h | 18 +--- firmware/steering/include/timers.h | 25 ------ firmware/steering/src/main.cpp | 9 +- firmware/steering/src/steering_control.cpp | 89 +++++++------------ firmware/steering/src/timers.cpp | 41 --------- firmware/throttle/CMakeLists.txt | 5 +- firmware/throttle/include/throttle_control.h | 20 +---- firmware/throttle/include/timers.h | 25 ------ firmware/throttle/src/main.cpp | 7 +- firmware/throttle/src/throttle_control.cpp | 80 ++++++----------- firmware/throttle/src/timers.cpp | 41 --------- 18 files changed, 97 insertions(+), 440 deletions(-) delete mode 100644 firmware/brake/kia_soul_ev/include/timers.h delete mode 100644 firmware/brake/kia_soul_ev/src/timers.cpp delete mode 100644 firmware/steering/include/timers.h delete mode 100644 firmware/steering/src/timers.cpp delete mode 100644 firmware/throttle/include/timers.h delete mode 100644 firmware/throttle/src/timers.cpp diff --git a/firmware/brake/kia_soul_ev/CMakeLists.txt b/firmware/brake/kia_soul_ev/CMakeLists.txt index ee6cdaa7..8c951d9e 100644 --- a/firmware/brake/kia_soul_ev/CMakeLists.txt +++ b/firmware/brake/kia_soul_ev/CMakeLists.txt @@ -9,13 +9,11 @@ generate_arduino_firmware( ${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) + src/init.cpp) target_include_directories( brake @@ -28,5 +26,4 @@ target_include_directories( ${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 index fa7468af..3bd4c180 100644 --- a/firmware/brake/kia_soul_ev/include/brake_control.h +++ b/firmware/brake/kia_soul_ev/include/brake_control.h @@ -43,31 +43,19 @@ typedef struct } 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. +// Purpose: Checks to see if valid values are being read from the sensors +// and if the vehicle's operator has manually pressed the brake +// pedal to disable if they have. // // Returns: void // // Parameters: void // // **************************************************************************** -void check_for_sensor_faults( void ); +void check_for_faults( void ); // **************************************************************************** diff --git a/firmware/brake/kia_soul_ev/include/timers.h b/firmware/brake/kia_soul_ev/include/timers.h deleted file mode 100644 index 7ce05c90..00000000 --- a/firmware/brake/kia_soul_ev/include/timers.h +++ /dev/null @@ -1,25 +0,0 @@ -/** - * @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/kia_soul_ev/src/brake_control.cpp b/firmware/brake/kia_soul_ev/src/brake_control.cpp index 883c057a..643976d2 100644 --- a/firmware/brake/kia_soul_ev/src/brake_control.cpp +++ b/firmware/brake/kia_soul_ev/src/brake_control.cpp @@ -17,93 +17,57 @@ #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 ) +void check_for_faults( void ) { - if ( g_brake_control_state.enabled == true - || g_brake_control_state.operator_override == true ) - { - brake_pedal_position_s brake_pedal_position; + brake_pedal_position_s brake_pedal_position; + if ( (g_brake_control_state.enabled == true) + || (g_brake_control_state.dtcs > 0) ) + { 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 ) + // sensor pins tied to ground - a value of zero indicates disconnection + if( (brake_pedal_position.high == 0) + || (brake_pedal_position.low == 0) ) { disable_control( ); DTC_SET( g_brake_control_state.dtcs, - OSCC_BRAKE_DTC_OPERATOR_OVERRIDE ); + OSCC_BRAKE_DTC_INVALID_SENSOR_VAL ); publish_fault_report( ); - g_brake_control_state.operator_override = true; - - DEBUG_PRINTLN( "Operator override" ); + DEBUG_PRINTLN( "Bad value read from brake pedal position sensor" ); } - else + else if ( brake_pedal_position_average >= BRAKE_PEDAL_OVERRIDE_THRESHOLD ) { - DTC_CLEAR( + disable_control( ); + + DTC_SET( 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( ); - publish_fault_report( ); + g_brake_control_state.operator_override = true; - DEBUG_PRINTLN( "Bad value read from brake pedal position sensor" ); - } + DEBUG_PRINTLN( "Operator override" ); } else { - DTC_CLEAR( - g_brake_control_state.dtcs, - OSCC_BRAKE_DTC_INVALID_SENSOR_VAL ); + g_brake_control_state.dtcs = 0; - fault_count = 0; + g_brake_control_state.operator_override = false; } } } diff --git a/firmware/brake/kia_soul_ev/src/main.cpp b/firmware/brake/kia_soul_ev/src/main.cpp index 7b800405..f0d2e8c8 100644 --- a/firmware/brake/kia_soul_ev/src/main.cpp +++ b/firmware/brake/kia_soul_ev/src/main.cpp @@ -9,7 +9,6 @@ #include "communications.h" #include "debug.h" #include "init.h" -#include "timers.h" int main( void ) @@ -22,14 +21,14 @@ int main( void ) init_communication_interfaces( ); - start_timers( ); - DEBUG_PRINTLN( "init complete" ); while( true ) { check_for_incoming_message( ); - check_for_operator_override( ); + check_for_faults( ); + + publish_brake_report( ); } } diff --git a/firmware/brake/kia_soul_ev/src/timers.cpp b/firmware/brake/kia_soul_ev/src/timers.cpp deleted file mode 100644 index 51dc4fb3..00000000 --- a/firmware/brake/kia_soul_ev/src/timers.cpp +++ /dev/null @@ -1,41 +0,0 @@ -/** - * @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_sensor_faults( ); - - sei(); -} diff --git a/firmware/steering/CMakeLists.txt b/firmware/steering/CMakeLists.txt index 4231b51d..252d5354 100644 --- a/firmware/steering/CMakeLists.txt +++ b/firmware/steering/CMakeLists.txt @@ -24,13 +24,11 @@ generate_arduino_firmware( ${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/init.cpp src/communications.cpp - src/steering_control.cpp - src/timers.cpp) + src/steering_control.cpp) target_include_directories( steering @@ -44,5 +42,4 @@ target_include_directories( ${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/steering/include/steering_control.h b/firmware/steering/include/steering_control.h index 9035fae9..95fc7c21 100644 --- a/firmware/steering/include/steering_control.h +++ b/firmware/steering/include/steering_control.h @@ -43,31 +43,19 @@ typedef struct } steering_control_state_s; -// **************************************************************************** -// Function: check_for_operator_override -// -// Purpose: Checks to see if the vehicle's operator has manually pressed -// the accelerator 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. +// If operator override for steering is turned on detection of the +// steering wheel being manually turned is also detected. // // Returns: void // // Parameters: void // // **************************************************************************** -void check_for_sensor_faults( void ); +void check_for_faults( void ); // **************************************************************************** diff --git a/firmware/steering/include/timers.h b/firmware/steering/include/timers.h deleted file mode 100644 index f99ee377..00000000 --- a/firmware/steering/include/timers.h +++ /dev/null @@ -1,25 +0,0 @@ -/** - * @file timers.h - * @brief Timer functionality. - * - */ - - -#ifndef _OSCC_STEERING_TIMERS_H_ -#define _OSCC_STEERING_TIMERS_H_ - - -// **************************************************************************** -// Function: start_timers -// -// Purpose: Start timers for report publishing and fault checking. -// -// Returns: void -// -// Parameters: void -// -// **************************************************************************** -void start_timers( void ); - - -#endif /* _OSCC_TH_OSCC_STEERING_TIMERS_H_ROTTLE_TIMERS_H_ */ diff --git a/firmware/steering/src/main.cpp b/firmware/steering/src/main.cpp index fdadf06b..74c1d54b 100644 --- a/firmware/steering/src/main.cpp +++ b/firmware/steering/src/main.cpp @@ -9,7 +9,6 @@ #include "debug.h" #include "init.h" #include "steering_control.h" -#include "timers.h" int main( void ) @@ -22,16 +21,14 @@ int main( void ) init_communication_interfaces( ); - start_timers( ); - DEBUG_PRINTLN( "init complete" ); while( true ) { check_for_incoming_message( ); -#ifdef STEERING_OVERRIDE - check_for_operator_override( ); -#endif + check_for_faults( ); + + publish_steering_report( ); } } diff --git a/firmware/steering/src/steering_control.cpp b/firmware/steering/src/steering_control.cpp index 27dacc63..88830cd2 100644 --- a/firmware/steering/src/steering_control.cpp +++ b/firmware/steering/src/steering_control.cpp @@ -18,12 +18,6 @@ #include "vehicles.h" -/* - * @brief Number of consecutive faults that can occur when reading the - * torque sensor before control is disabled. - * - */ -#define SENSOR_VALIDITY_CHECK_FAULT_COUNT ( 4 ) static void read_torque_sensor( @@ -34,19 +28,20 @@ static float exponential_moving_average( const float input, const float average ); - +#ifdef STEERING_OVERRIDE static uint16_t filtered_diff = 0; +#endif - -void check_for_operator_override( void ) +void check_for_faults( void ) { - if( g_steering_control_state.enabled == true - || g_steering_control_state.operator_override == true ) - { - steering_torque_s torque; + steering_torque_s torque; - read_torque_sensor( &torque ); + if ( ( g_steering_control_state.enabled == true ) + || (g_steering_control_state.dtcs > 0) ) + { + read_torque_sensor(&torque); +#ifdef STEERING_OVERRIDE uint16_t unfiltered_diff = abs( ( int )torque.high - ( int )torque.low ); const float filter_alpha = 0.01; @@ -60,70 +55,45 @@ void check_for_operator_override( void ) filter_alpha, unfiltered_diff, filtered_diff); +#endif - if( abs( filtered_diff ) > TORQUE_DIFFERENCE_OVERRIDE_THRESHOLD ) + // sensor pins tied to ground - a value of zero indicates disconnection + if( (torque.high == 0) + || (torque.low == 0) ) { disable_control( ); DTC_SET( g_steering_control_state.dtcs, - OSCC_STEERING_DTC_OPERATOR_OVERRIDE ); + OSCC_STEERING_DTC_INVALID_SENSOR_VAL ); publish_fault_report( ); - g_steering_control_state.operator_override = true; - - DEBUG_PRINTLN( "Operator override" ); + DEBUG_PRINTLN( "Bad value read from torque sensor" ); } - else +#ifdef STEERING_OVERRIDE + else if( abs( filtered_diff ) > TORQUE_DIFFERENCE_OVERRIDE_THRESHOLD ) { - DTC_CLEAR( + disable_control( ); + + DTC_SET( g_steering_control_state.dtcs, OSCC_STEERING_DTC_OPERATOR_OVERRIDE ); - g_steering_control_state.operator_override = false; - } - } -} - - -void check_for_sensor_faults( void ) -{ - if ( (g_steering_control_state.enabled == true) - || DTC_CHECK(g_steering_control_state.dtcs, OSCC_STEERING_DTC_INVALID_SENSOR_VAL) ) - { - static int fault_count = 0; - - steering_torque_s torque; - - read_torque_sensor(&torque); - - // sensor pins tied to ground - a value of zero indicates disconnection - if( (torque.high == 0) - || (torque.low == 0) ) - { - ++fault_count; - - if( fault_count >= SENSOR_VALIDITY_CHECK_FAULT_COUNT ) - { - disable_control( ); - - DTC_SET( - g_steering_control_state.dtcs, - OSCC_STEERING_DTC_INVALID_SENSOR_VAL ); + publish_fault_report( ); - publish_fault_report( ); + g_steering_control_state.operator_override = true; - DEBUG_PRINTLN( "Bad value read from torque sensor" ); - } + DEBUG_PRINTLN( "Operator override" ); } +#endif else { - DTC_CLEAR( - g_steering_control_state.dtcs, - OSCC_STEERING_DTC_INVALID_SENSOR_VAL ); + g_steering_control_state.dtcs = 0; - fault_count = 0; +#ifdef STEERING_OVERRIDE + g_steering_control_state.operator_override = false; +#endif } } } @@ -195,7 +165,9 @@ void disable_control( void ) g_steering_control_state.enabled = false; +#ifdef STEERING_OVERRIDE filtered_diff = 0; +#endif DEBUG_PRINTLN( "Control disabled" ); } @@ -217,4 +189,3 @@ static void read_torque_sensor( value->low = analogRead( PIN_TORQUE_SENSOR_LOW ) << 2; sei(); } - diff --git a/firmware/steering/src/timers.cpp b/firmware/steering/src/timers.cpp deleted file mode 100644 index 67207759..00000000 --- a/firmware/steering/src/timers.cpp +++ /dev/null @@ -1,41 +0,0 @@ -/** - * @file timers.cpp - * - */ - - -#include - -#include "can_protocols/steering_can_protocol.h" -#include "communications.h" -#include "globals.h" -#include "oscc_timer.h" -#include "steering_control.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_REPORT_STEERING_PUBLISH_FREQ_IN_HZ, publish_steering_report ); -} - - -static void check_for_faults( void ) -{ - cli(); - - check_for_sensor_faults( ); - - sei(); -} diff --git a/firmware/throttle/CMakeLists.txt b/firmware/throttle/CMakeLists.txt index 50c505b8..fbbe568a 100644 --- a/firmware/throttle/CMakeLists.txt +++ b/firmware/throttle/CMakeLists.txt @@ -23,13 +23,11 @@ generate_arduino_firmware( ${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/init.cpp src/communications.cpp - src/throttle_control.cpp - src/timers.cpp) + src/throttle_control.cpp) target_include_directories( throttle @@ -42,5 +40,4 @@ target_include_directories( ${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/throttle/include/throttle_control.h b/firmware/throttle/include/throttle_control.h index 1fe9c3dc..9a84dc78 100644 --- a/firmware/throttle/include/throttle_control.h +++ b/firmware/throttle/include/throttle_control.h @@ -43,31 +43,19 @@ typedef struct } throttle_control_state_s; -// **************************************************************************** -// Function: check_for_operator_override -// -// Purpose: Checks to see if the vehicle's operator has manually pressed -// the accelerator 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. +// Purpose: Checks to see if valid values are being read from the sensors +// and if the vehicle's operator has manually pressed the +// accelerator to disable control if they have. // // Returns: void // // Parameters: void // // **************************************************************************** -void check_for_sensor_faults( void ); +void check_for_faults( void ); // **************************************************************************** diff --git a/firmware/throttle/include/timers.h b/firmware/throttle/include/timers.h deleted file mode 100644 index cefc8cae..00000000 --- a/firmware/throttle/include/timers.h +++ /dev/null @@ -1,25 +0,0 @@ -/** - * @file timers.h - * @brief Timer functionality. - * - */ - - -#ifndef _OSCC_THROTTLE_TIMERS_H_ -#define _OSCC_THROTTLE_TIMERS_H_ - - -// **************************************************************************** -// Function: start_timers -// -// Purpose: Start timers for report publishing and fault checking. -// -// Returns: void -// -// Parameters: void -// -// **************************************************************************** -void start_timers( void ); - - -#endif /* _OSCC_THROTTLE_TIMERS_H_ */ diff --git a/firmware/throttle/src/main.cpp b/firmware/throttle/src/main.cpp index c399890a..18856558 100644 --- a/firmware/throttle/src/main.cpp +++ b/firmware/throttle/src/main.cpp @@ -8,7 +8,6 @@ #include "communications.h" #include "debug.h" #include "init.h" -#include "timers.h" #include "throttle_control.h" @@ -22,14 +21,14 @@ int main( void ) init_communication_interfaces( ); - start_timers( ); - DEBUG_PRINTLN( "init complete" ); while( true ) { check_for_incoming_message( ); - check_for_operator_override( ); + check_for_faults( ); + + publish_throttle_report( ); } } diff --git a/firmware/throttle/src/throttle_control.cpp b/firmware/throttle/src/throttle_control.cpp index 9a77224c..dc7c2561 100644 --- a/firmware/throttle/src/throttle_control.cpp +++ b/firmware/throttle/src/throttle_control.cpp @@ -17,93 +17,61 @@ #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_accelerator_position_sensor( accelerator_position_s * const value ); -void check_for_operator_override( void ) +void check_for_faults( void ) { - if ( g_throttle_control_state.enabled == true - || g_throttle_control_state.operator_override == true ) - { - accelerator_position_s accelerator_position; + accelerator_position_s accelerator_position; + if ( ( g_throttle_control_state.enabled == true ) + || (g_throttle_control_state.dtcs > 0) ) + { read_accelerator_position_sensor( &accelerator_position ); uint32_t accelerator_position_average = (accelerator_position.low + accelerator_position.high) / 2; - if ( accelerator_position_average >= ACCELERATOR_OVERRIDE_THRESHOLD ) + // sensor pins tied to ground - a value of zero indicates disconnection + if( (accelerator_position.high == 0) + || (accelerator_position.low == 0) ) { disable_control( ); DTC_SET( g_throttle_control_state.dtcs, - OSCC_THROTTLE_DTC_OPERATOR_OVERRIDE ); + OSCC_THROTTLE_DTC_INVALID_SENSOR_VAL ); publish_fault_report( ); - g_throttle_control_state.operator_override = true; - - DEBUG_PRINTLN( "Operator override" ); + DEBUG_PRINTLN( "Bad value read from accelerator position sensor" ); } - else + else if ( accelerator_position_average >= ACCELERATOR_OVERRIDE_THRESHOLD + && g_throttle_control_state.operator_override == false ) { - DTC_CLEAR( + disable_control( ); + + DTC_SET( g_throttle_control_state.dtcs, OSCC_THROTTLE_DTC_OPERATOR_OVERRIDE ); - g_throttle_control_state.operator_override = false; - } - } -} - - -void check_for_sensor_faults( void ) -{ - if ( (g_throttle_control_state.enabled == true) - || DTC_CHECK(g_throttle_control_state.dtcs, OSCC_THROTTLE_DTC_INVALID_SENSOR_VAL) ) - { - static int fault_count = 0; - - accelerator_position_s accelerator_position; - - read_accelerator_position_sensor( &accelerator_position ); - - // sensor pins tied to ground - a value of zero indicates disconnection - if( (accelerator_position.high == 0) - || (accelerator_position.low == 0) ) - { - ++fault_count; - - if( fault_count >= SENSOR_VALIDITY_CHECK_FAULT_COUNT ) - { - disable_control( ); - - DTC_SET( - g_throttle_control_state.dtcs, - OSCC_THROTTLE_DTC_INVALID_SENSOR_VAL ); + publish_fault_report( ); - publish_fault_report( ); + g_throttle_control_state.operator_override = true; - DEBUG_PRINTLN( "Bad value read from accelerator position sensor" ); - } + DEBUG_PRINTLN( "Operator override" ); } else { - DTC_CLEAR( - g_throttle_control_state.dtcs, - OSCC_THROTTLE_DTC_INVALID_SENSOR_VAL ); + g_throttle_control_state.dtcs = 0; - fault_count = 0; + if ( g_throttle_control_state.operator_override == true ) + { + g_throttle_control_state.operator_override = false; + } } } } @@ -141,6 +109,7 @@ void enable_control( void ) && g_throttle_control_state.operator_override == false ) { const uint16_t num_samples = 20; + //TODO: Should this be inside the cli()?!? prevent_signal_discontinuity( g_dac, num_samples, @@ -163,6 +132,7 @@ void disable_control( void ) if( g_throttle_control_state.enabled == true ) { const uint16_t num_samples = 20; + //TODO: Should this be inside the cli()?!? prevent_signal_discontinuity( g_dac, num_samples, diff --git a/firmware/throttle/src/timers.cpp b/firmware/throttle/src/timers.cpp deleted file mode 100644 index 4c90918b..00000000 --- a/firmware/throttle/src/timers.cpp +++ /dev/null @@ -1,41 +0,0 @@ -/** - * @file timers.cpp - * - */ - - -#include - -#include "can_protocols/throttle_can_protocol.h" -#include "communications.h" -#include "globals.h" -#include "oscc_timer.h" -#include "throttle_control.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_REPORT_THROTTLE_PUBLISH_FREQ_IN_HZ, publish_throttle_report ); -} - - -static void check_for_faults( void ) -{ - cli(); - - check_for_sensor_faults( ); - - sei(); -} From f1286a7faedf2e88b66737da699697aeecb88139 Mon Sep 17 00:00:00 2001 From: Shea Newton Date: Mon, 8 Jan 2018 12:53:41 -0800 Subject: [PATCH 57/84] 'project' misspelling caught in review. fixed. --- api/README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/api/README.md b/api/README.md index 4d4c9d19..325c2333 100644 --- a/api/README.md +++ b/api/README.md @@ -20,7 +20,7 @@ for the Kia Soul Petrol instead. ### Using `libosccapi.so` Using the shared library for a project that uses the OSCC API is easy! The following is an example `CMakeLists.txt` for doing just that. This example -is all you need for a projec with it's own source file, `main.c`. +is all you need for a project with it's own source file, `main.c`. ``` cmake_minimum_required(VERSION 2.8) project(an_example) From cfe3142b107fd29592fc4c201a15e9b27e01f9e9 Mon Sep 17 00:00:00 2001 From: Shea Newton Date: Mon, 8 Jan 2018 12:57:32 -0800 Subject: [PATCH 58/84] Address issue raised in PT. Propmt for firmware version as well as project/API version --- .github/ISSUE_TEMPLATE.md | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/.github/ISSUE_TEMPLATE.md b/.github/ISSUE_TEMPLATE.md index 0267d0d5..cb569816 100644 --- a/.github/ISSUE_TEMPLATE.md +++ b/.github/ISSUE_TEMPLATE.md @@ -28,7 +28,8 @@ tackle it! ### Version info -_What's the output of running `git describe --tags` in your OSCC directory?_ +- _What's the output of running `git describe --tags` in your OSCC directory?_ +- _Is this the same version flashed onto the hardware?_ ### Hardware info From 2dfa29f35db79f62c933da7c3f0a10d67e0dc4ad Mon Sep 17 00:00:00 2001 From: Shea Newton Date: Mon, 8 Jan 2018 13:20:11 -0800 Subject: [PATCH 59/84] Take recommendation and remove the word 'libaraly' from template comment, it didn't add much. --- .github/ISSUE_TEMPLATE.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/ISSUE_TEMPLATE.md b/.github/ISSUE_TEMPLATE.md index cb569816..2d752171 100644 --- a/.github/ISSUE_TEMPLATE.md +++ b/.github/ISSUE_TEMPLATE.md @@ -3,7 +3,7 @@ Thanks for filing an OSCC issue! You're making our ecosystem a better place! Below are some templates to get you started, filling out any that are relevant to this issue will help us a lot! Feel free to delete any information or text -that isn't relevant to your issue liberally. +that isn't relevant to your issue. -->