├── .gitattributes ├── .gitignore ├── AndroidCar.h ├── Car.cpp ├── Gyroscope.cpp ├── LED_DRIVER ├── LED_DRIVER.ino ├── README.md ├── res │ ├── eagle │ │ ├── LICENSE │ │ ├── led_driver.brd │ │ └── led_driver.sch │ ├── led_controller_schem.png │ ├── led_driver_back_render.png │ └── led_driver_front_render.png └── variables.h ├── LICENSE ├── MouseSensor.cpp ├── NewPing.cpp ├── Odometer.cpp ├── README.md ├── Razorboard.cpp ├── SRF08.cpp ├── Sharp_IR.cpp ├── Sonar.cpp ├── examples └── androidCar │ ├── CarVariables.h │ ├── README.md │ ├── androidCar.ino │ └── res │ ├── android_vehicle_bb.png │ └── system_schematic.png └── keywords.txt /.gitattributes: -------------------------------------------------------------------------------- 1 | LED_DRIVER/res/* linguist-vendored -------------------------------------------------------------------------------- /.gitignore: -------------------------------------------------------------------------------- 1 | # Ignore gedit backup files # 2 | *.ino~ 3 | *.cpp~ 4 | *.h~ -------------------------------------------------------------------------------- /AndroidCar.h: -------------------------------------------------------------------------------- 1 | /* 2 | * AndroidCar.h - A simple library for controlling the smartcar 3 | * sensors. 4 | * Version: 0.3 5 | * Author: Dimitris Platis 6 | * Sonar class is essentially a stripped-down version of the NewPing library by Tim Eckel, adjusted to Smartcar needs 7 | * Get original library at: http://code.google.com/p/arduino-new-ping/ 8 | * License: GNU GPL v3 http://www.gnu.org/licenses/gpl-3.0.html 9 | */ 10 | 11 | #ifndef AndroidCar_h 12 | #define AndroidCar_h 13 | #if defined(ARDUINO) && ARDUINO >= 100 14 | #include 15 | #else 16 | #include 17 | #include 18 | #endif 19 | #include 20 | #include 21 | #include 22 | #include 23 | 24 | class Car { 25 | public: 26 | Car(unsigned short steeringWheelPin = DEFAULT_SERVO_PIN, unsigned short escPin = DEFAULT_ESC_PIN); 27 | void begin(); 28 | void setSpeed(int speed); 29 | void setAngle(int degrees); 30 | int getSpeed(); 31 | int getAngle(); 32 | private: 33 | void setSteeringWheelPin(unsigned short steeringWheelPin); 34 | void setESCPin(unsigned short escPin); 35 | unsigned short _steeringWheelPin, _escPin; 36 | Servo motor, steeringWheel; 37 | int _speed, _angle; 38 | static const unsigned short DEFAULT_SERVO_PIN, DEFAULT_ESC_PIN; 39 | }; 40 | 41 | class Sonar { 42 | public: 43 | Sonar(); 44 | void attach(unsigned short triggerPin, unsigned short echoPin); 45 | unsigned int getDistance(); 46 | unsigned int getMedianDistance(short iterations = SONAR_DEFAULT_ITERATIONS); 47 | 48 | private: 49 | unsigned int ping(); 50 | boolean ping_trigger(); 51 | uint8_t _triggerBit; 52 | uint8_t _echoBit; 53 | volatile uint8_t *_triggerOutput; 54 | volatile uint8_t *_triggerMode; 55 | volatile uint8_t *_echoInput; 56 | unsigned int _maxEchoTime; 57 | unsigned long _max_time; 58 | static const unsigned short SONAR_DEFAULT_ITERATIONS; 59 | }; 60 | 61 | class Sharp_IR { 62 | public: 63 | Sharp_IR(); 64 | void attach(unsigned short IR_pin); 65 | unsigned int getDistance(); 66 | unsigned int getMedianDistance(short iterations = IR_DEFAULT_ITERATIONS); 67 | private: 68 | unsigned short _IR_pin; 69 | static const unsigned short IR_DEFAULT_ITERATIONS; 70 | }; 71 | 72 | 73 | class Odometer { 74 | public: 75 | Odometer(); 76 | int attach(unsigned short odometerPin); 77 | void begin(); 78 | unsigned long getDistance(); 79 | void detach(); 80 | private: 81 | unsigned short _odometerInterruptPin; 82 | }; 83 | 84 | class NewPing{ 85 | public: 86 | static void timer_start(unsigned long frequency, void (*userFunc)(void)); 87 | static void timer_stop(); 88 | private: 89 | static void timer_setup(); 90 | static void timer_start_cntdwn(); 91 | }; 92 | 93 | class Gyroscope { 94 | public: 95 | Gyroscope(); 96 | void attach(); 97 | void begin(unsigned short samplingRate = DEFAULT_GYRO_SAMPLING); //in milliseconds 98 | int getAngularDisplacement(); 99 | void update(); 100 | private: 101 | void initMeasurement(); 102 | void initializeGyro(); 103 | int setupL3G4200D(int scale); 104 | void writeRegister(int deviceAddress, byte address, byte val); 105 | int getGyroValues(); 106 | int readRegister(int deviceAddress, byte address); 107 | unsigned short _samplingRate; 108 | static const unsigned short DEFAULT_GYRO_SAMPLING; 109 | }; 110 | 111 | class Razorboard{ 112 | public: 113 | Razorboard(); 114 | void attach(HardwareSerial *razorSerial); 115 | boolean available(); 116 | String readLine(); 117 | String readLastLine(); 118 | int getHeading(); 119 | int getLatestHeading(); 120 | private: 121 | String readRawSerialLine(); 122 | int getRawHeading(); 123 | HardwareSerial * _serial; 124 | }; 125 | 126 | class MouseSensor{ 127 | public: 128 | MouseSensor(); 129 | void attach(HardwareSerial *mouseSerial); 130 | boolean available(); 131 | String readLine(); 132 | String readLastLine(); 133 | int getX(String mouseInput); 134 | int getY(String mouseInput); 135 | void clear(); 136 | private: 137 | String readRawSerialLine(); 138 | HardwareSerial * _serial; 139 | }; 140 | 141 | class SRF08{ 142 | public: 143 | SRF08(); 144 | void attach(const uint8_t address = DEFAULT_SRF08_ADDRESS); 145 | void setGain(const uint8_t gainValue); 146 | void setRange(const uint8_t rangeValue); 147 | void setPingDelay(const uint8_t milliseconds = DEFAULT_PING_DELAY); 148 | int getDistance(); 149 | void changeAddress(const uint8_t newAddress); 150 | private: 151 | int ping(); 152 | uint8_t _address, _delay; 153 | static const uint8_t DEFAULT_PING_DELAY, DEFAULT_SRF08_ADDRESS; 154 | 155 | }; 156 | 157 | #endif 158 | -------------------------------------------------------------------------------- /Car.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | * Car.cpp 3 | */ 4 | #include "AndroidCar.h" 5 | /* --- CAR --- */ 6 | 7 | const unsigned short Car::DEFAULT_SERVO_PIN = 8; 8 | const unsigned short Car::DEFAULT_ESC_PIN = 9; 9 | 10 | const int IDLE_SPEED = 1500; 11 | const int MAX_FRONT_SPEED = 1590; //can go to 1800 12 | const int MAX_BACK_SPEED = 1200; //can go to 1200 13 | const int STRAIGHT_WHEELS = 97; 14 | const int MAX_RIGHT_DEGREES = 122; 15 | const int MAX_LEFT_DEGREES = 72; 16 | 17 | Car::Car(unsigned short steeringWheelPin, unsigned short escPin){ 18 | setSteeringWheelPin(steeringWheelPin); 19 | setESCPin(escPin); 20 | } 21 | 22 | void Car::begin(){ 23 | motor.attach(_escPin); 24 | steeringWheel.attach(_steeringWheelPin); 25 | setSpeed(0); 26 | setAngle(0); 27 | } 28 | 29 | void Car::setSteeringWheelPin(unsigned short steeringWheelPin){ 30 | _steeringWheelPin = steeringWheelPin; 31 | } 32 | 33 | void Car::setESCPin(unsigned short escPin){ 34 | _escPin = escPin; 35 | } 36 | 37 | void Car::setSpeed(int speed){ 38 | _speed = constrain(IDLE_SPEED + speed, MAX_BACK_SPEED, MAX_FRONT_SPEED); 39 | motor.write(_speed); 40 | } 41 | 42 | void Car::setAngle(int degrees){ 43 | _angle = constrain(STRAIGHT_WHEELS + degrees, MAX_LEFT_DEGREES, MAX_RIGHT_DEGREES); 44 | steeringWheel.write(_angle); 45 | } 46 | 47 | int Car::getSpeed(){ 48 | return _speed - IDLE_SPEED; 49 | } 50 | 51 | int Car::getAngle(){ 52 | return _angle - STRAIGHT_WHEELS; 53 | } 54 | -------------------------------------------------------------------------------- /Gyroscope.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | * Odometer.cpp - Handles the gyroscope (L3G4200D) sensor of the Smartcar. 3 | * Version: 0.3 4 | * Author: Dimitris Platis (based on the bildr.org example: http://bildr.org/2011/06/l3g4200d-arduino/) 5 | * License: GNU GPL v3 http://www.gnu.org/licenses/gpl-3.0.html 6 | */ 7 | 8 | #include "AndroidCar.h" 9 | 10 | 11 | /* ---- GYROSCOPE (L3G4200D) ---- */ 12 | const unsigned short Gyroscope::DEFAULT_GYRO_SAMPLING = 25; 13 | static const int GYRO_OFFSET = 57; //The value that is usually given by the gyroscope when not moving. Determined experimentally, adapt accordingly. 14 | static const float GYRO_SENSITIVITY = 0.07; //L3G4200D specific. 15 | static const int GYRO_THRESHOLD = 12; //Tolerance threshold. Determined experimentally, adapt accordingly. 16 | static const int CTRL_REG1 = 0x20; 17 | static const int CTRL_REG2 = 0x21; 18 | static const int CTRL_REG3 = 0x22; 19 | static const int CTRL_REG4 = 0x23; 20 | static const int CTRL_REG5 = 0x24; 21 | static const int L3G4200D_Address = 105; //gyroscope I2C address 22 | volatile int _angularDisplacement = 0; 23 | volatile unsigned long _prevSample = 0; 24 | 25 | Gyroscope::Gyroscope(){ 26 | } 27 | 28 | void Gyroscope::attach(){ 29 | initializeGyro(); 30 | } 31 | 32 | void Gyroscope::initMeasurement(){ 33 | _angularDisplacement = 0; 34 | _prevSample = 0; 35 | } 36 | 37 | void Gyroscope::begin(unsigned short samplingRate){ 38 | initMeasurement(); 39 | _prevSample = millis(); 40 | _samplingRate = samplingRate; 41 | } 42 | 43 | int Gyroscope::getAngularDisplacement(){ 44 | return _angularDisplacement; 45 | } 46 | 47 | /* based on http://www.pieter-jan.com/node/7 integration algorithm */ 48 | void Gyroscope::update(){ 49 | if (millis()- _prevSample > _samplingRate){ 50 | float gyroRate = 0; 51 | int gyroValue = getGyroValues(); 52 | short drift = GYRO_OFFSET - gyroValue; 53 | if (abs(drift) > GYRO_THRESHOLD){ 54 | gyroRate = (gyroValue - GYRO_OFFSET) * GYRO_SENSITIVITY; 55 | } 56 | unsigned long now = millis(); 57 | _angularDisplacement += gyroRate / (1000 / (now - _prevSample)); 58 | _prevSample = now; 59 | } 60 | } 61 | 62 | void Gyroscope::initializeGyro(){ 63 | Wire.begin(); 64 | setupL3G4200D(2000); // Configure L3G4200 at 2000 deg/sec. Other options: 250, 500 (NOT suggested, will have to redetermine offset) 65 | } 66 | 67 | /* based on the bildr.org example: http://bildr.org/2011/06/l3g4200d-arduino/ */ 68 | int Gyroscope::getGyroValues(){ 69 | byte zMSB = readRegister(L3G4200D_Address, 0x2D); 70 | byte zLSB = readRegister(L3G4200D_Address, 0x2C); 71 | return ((zMSB << 8) | zLSB); 72 | } 73 | 74 | int Gyroscope::setupL3G4200D(int scale){ 75 | //From Jim Lindblom of Sparkfun's code 76 | 77 | // Enable x, y, z and turn off power down: 78 | writeRegister(L3G4200D_Address, CTRL_REG1, 0b00001111); 79 | 80 | // If you'd like to adjust/use the HPF, you can edit the line below to configure CTRL_REG2: 81 | writeRegister(L3G4200D_Address, CTRL_REG2, 0b00000000); 82 | 83 | // Configure CTRL_REG3 to generate data ready interrupt on INT2 84 | // No interrupts used on INT1, if you'd like to configure INT1 85 | // or INT2 otherwise, consult the datasheet: 86 | writeRegister(L3G4200D_Address, CTRL_REG3, 0b00001000); 87 | 88 | // CTRL_REG4 controls the full-scale range, among other things: 89 | 90 | if(scale == 250){ 91 | writeRegister(L3G4200D_Address, CTRL_REG4, 0b00000000); 92 | }else if(scale == 500){ 93 | writeRegister(L3G4200D_Address, CTRL_REG4, 0b00010000); 94 | }else{ 95 | writeRegister(L3G4200D_Address, CTRL_REG4, 0b00110000); 96 | } 97 | 98 | // CTRL_REG5 controls high-pass filtering of outputs, use it 99 | // if you'd like: 100 | writeRegister(L3G4200D_Address, CTRL_REG5, 0b00000000); 101 | } 102 | 103 | void Gyroscope::writeRegister(int deviceAddress, byte address, byte val) { 104 | Wire.beginTransmission(deviceAddress); // start transmission to device 105 | Wire.write(address); // send register address 106 | Wire.write(val); // send value to write 107 | Wire.endTransmission(); // end transmission 108 | } 109 | 110 | int Gyroscope::readRegister(int deviceAddress, byte address){ 111 | int v; 112 | Wire.beginTransmission(deviceAddress); 113 | Wire.write(address); // register to read 114 | Wire.endTransmission(); 115 | Wire.requestFrom(deviceAddress, 1); // read a byte 116 | 117 | if (!Wire.available()) return -1; 118 | 119 | v = Wire.read(); 120 | 121 | return v; 122 | } 123 | -------------------------------------------------------------------------------- /LED_DRIVER/LED_DRIVER.ino: -------------------------------------------------------------------------------- 1 | #include 2 | #include "variables.h" 3 | 4 | SoftwareSerial serialInput(RX_PIN, UNUSED_TX_PIN); //rx,tx 5 | 6 | State currentState = STOP; 7 | boolean stateChanged = false; 8 | const uint8_t LED_TOGGLE_STATES[5][2] = { //array to hold the various states the LEDs can be. Each row represents one LED, in accordance to State values, as enumerated in variables.h 9 | {HIGH, LOW}, 10 | {HIGH, HIGH}, //the stop lights are always high 11 | {LOW, LOW}, //not used 12 | {HIGH, LOW}, 13 | {HIGH, LOW} 14 | }; //for example, using digitalWrite(RIGHT, LED_TOGGLE_STATES[RIGHT][0]) would set the RIGHT pin to its first state (HIGH in this case) 15 | boolean ledToggleVal = false; //controls whether the respective pin will be LOW or HIGH. for example LED_TOGGLE_STATES[RIGHT][ledToggleVal] when ledToggleVal is false, means that when used in a digital write, the specified pin (RIGHT) should be set to HIGH 16 | boolean ledToggled = false; //flag to indicate whether there has been a LED toggling. Used to determine whether it is necessary to digitalWrite or not (there is nothing "new" to be written) 17 | unsigned long prevToggle = 0; //the moment the previous LED toggling occurred 18 | const unsigned short LED_INTERVAL = 1000; //how often we should toggle the LED state (simply: how often we should blink the lights) 19 | 20 | void setup() { 21 | serialInput.begin(9600); 22 | pinMode(STOP, OUTPUT); 23 | pinMode(RIGHT, OUTPUT); 24 | pinMode(LEFT, OUTPUT); 25 | pinMode(RC, OUTPUT); 26 | noLights(); //initialize all the LEDs to low 27 | } 28 | 29 | void loop() { 30 | handleInput(); //if there is input on the SoftwareSerial RX pin, match it to a specific state 31 | handleLEDs(); //decide on which LEDs to light up, depending on the current state and whether this just changed 32 | } 33 | 34 | void handleInput() { 35 | if (serialInput.available()) { 36 | char inChar; 37 | while (serialInput.available()) inChar = serialInput.read(); //read through the buffer and keep the last character disregarding what came in the meanwhile 38 | switch (inChar) { 39 | case 'l': 40 | setState(LEFT); 41 | break; 42 | case 'r': 43 | setState(RIGHT); 44 | break; 45 | case 'm': 46 | setState(RC); 47 | break; 48 | case 's': 49 | setState(STOP); 50 | break; 51 | default: 52 | setState(MOVING_STRAIGHT); 53 | break; 54 | } 55 | } 56 | } 57 | 58 | void setState(State state) { 59 | if (currentState != state) stateChanged = true; //indicate that we have just changed the state 60 | currentState = state; //log down the new state 61 | } 62 | 63 | void handleLEDs() { 64 | if (stateChanged){ //if the state was just changed then we should re-initialize the led toggling sequence 65 | noLights(); //turn off all the LEDs, so whatever was previously on, will turn off now 66 | ledToggleVal = false; //start the ledToggle from the beginning 67 | ledToggled = true; //indicate the has been a led toggle 68 | prevToggle = millis(); //start the new toggle 69 | stateChanged = false; //acknowledge that we are aware of the state change and set it back to false 70 | } 71 | if (millis() > prevToggle + LED_INTERVAL){ //if it is time to toggle the state of the LED 72 | ledToggleVal = !ledToggleVal; //change the state 73 | ledToggled = true; //indicate the has been a led toggle 74 | prevToggle = millis(); //save the moment when this happened 75 | } 76 | if ((currentState != MOVING_STRAIGHT) && ledToggled){ //if we are not MOVING_FORWARD (thus all LEDs are off) then toggle the led state AND there has been a toggled LED 77 | digitalWrite(currentState, LED_TOGGLE_STATES[currentState][ledToggleVal]); //write the status of the led, on the appropriate pin (states match to pins) 78 | ledToggled = false; //indicate that the led has been toggled in this specific state, so this doesn't need to be run again 79 | } 80 | } 81 | 82 | void noLights() { //turn all lights off 83 | digitalWrite(RIGHT, LOW); 84 | digitalWrite(LEFT, LOW); 85 | digitalWrite(STOP, LOW); 86 | digitalWrite(RC, LOW); 87 | } 88 | -------------------------------------------------------------------------------- /LED_DRIVER/README.md: -------------------------------------------------------------------------------- 1 | # LED DRIVER 2 | The LED driver board, is based on an ATTiny85 microcontroller and is used in order to drive the LEDs that can be found on the vehicle and particularly the direction indicators. In the [/res](res) folder, you can find the board's schema, how it looks like and also the Eagle files if you want to modify it or fabricate it yourself. Moreover, if you want just to reproduce the board, you can order it from [OSH Park](https://oshpark.com/shared_projects/Hk4up6hJ). 3 | 4 | ### Materials used 5 | * 6 screw terminals ([Sparkfun](https://www.sparkfun.com/products/8432)) 6 | * 4 NPN transistors (BC547) 7 | * 4 1.5KΩ resistors 8 | * 1 ATtiny85-20PU microcontroller 9 | * 1 socket 8 DIP (optional but strongly recommended) -------------------------------------------------------------------------------- /LED_DRIVER/res/eagle/LICENSE: -------------------------------------------------------------------------------- 1 | Creative Commons Legal Code 2 | 3 | Attribution 3.0 Unported 4 | 5 | CREATIVE COMMONS CORPORATION IS NOT A LAW FIRM AND DOES NOT PROVIDE 6 | LEGAL SERVICES. DISTRIBUTION OF THIS LICENSE DOES NOT CREATE AN 7 | ATTORNEY-CLIENT RELATIONSHIP. CREATIVE COMMONS PROVIDES THIS 8 | INFORMATION ON AN "AS-IS" BASIS. CREATIVE COMMONS MAKES NO WARRANTIES 9 | REGARDING THE INFORMATION PROVIDED, AND DISCLAIMS LIABILITY FOR 10 | DAMAGES RESULTING FROM ITS USE. 11 | 12 | License 13 | 14 | THE WORK (AS DEFINED BELOW) IS PROVIDED UNDER THE TERMS OF THIS CREATIVE 15 | COMMONS PUBLIC LICENSE ("CCPL" OR "LICENSE"). THE WORK IS PROTECTED BY 16 | COPYRIGHT AND/OR OTHER APPLICABLE LAW. ANY USE OF THE WORK OTHER THAN AS 17 | AUTHORIZED UNDER THIS LICENSE OR COPYRIGHT LAW IS PROHIBITED. 18 | 19 | BY EXERCISING ANY RIGHTS TO THE WORK PROVIDED HERE, YOU ACCEPT AND AGREE 20 | TO BE BOUND BY THE TERMS OF THIS LICENSE. TO THE EXTENT THIS LICENSE MAY 21 | BE CONSIDERED TO BE A CONTRACT, THE LICENSOR GRANTS YOU THE RIGHTS 22 | CONTAINED HERE IN CONSIDERATION OF YOUR ACCEPTANCE OF SUCH TERMS AND 23 | CONDITIONS. 24 | 25 | 1. Definitions 26 | 27 | a. "Adaptation" means a work based upon the Work, or upon the Work and 28 | other pre-existing works, such as a translation, adaptation, 29 | derivative work, arrangement of music or other alterations of a 30 | literary or artistic work, or phonogram or performance and includes 31 | cinematographic adaptations or any other form in which the Work may be 32 | recast, transformed, or adapted including in any form recognizably 33 | derived from the original, except that a work that constitutes a 34 | Collection will not be considered an Adaptation for the purpose of 35 | this License. For the avoidance of doubt, where the Work is a musical 36 | work, performance or phonogram, the synchronization of the Work in 37 | timed-relation with a moving image ("synching") will be considered an 38 | Adaptation for the purpose of this License. 39 | b. "Collection" means a collection of literary or artistic works, such as 40 | encyclopedias and anthologies, or performances, phonograms or 41 | broadcasts, or other works or subject matter other than works listed 42 | in Section 1(f) below, which, by reason of the selection and 43 | arrangement of their contents, constitute intellectual creations, in 44 | which the Work is included in its entirety in unmodified form along 45 | with one or more other contributions, each constituting separate and 46 | independent works in themselves, which together are assembled into a 47 | collective whole. A work that constitutes a Collection will not be 48 | considered an Adaptation (as defined above) for the purposes of this 49 | License. 50 | c. "Distribute" means to make available to the public the original and 51 | copies of the Work or Adaptation, as appropriate, through sale or 52 | other transfer of ownership. 53 | d. "Licensor" means the individual, individuals, entity or entities that 54 | offer(s) the Work under the terms of this License. 55 | e. "Original Author" means, in the case of a literary or artistic work, 56 | the individual, individuals, entity or entities who created the Work 57 | or if no individual or entity can be identified, the publisher; and in 58 | addition (i) in the case of a performance the actors, singers, 59 | musicians, dancers, and other persons who act, sing, deliver, declaim, 60 | play in, interpret or otherwise perform literary or artistic works or 61 | expressions of folklore; (ii) in the case of a phonogram the producer 62 | being the person or legal entity who first fixes the sounds of a 63 | performance or other sounds; and, (iii) in the case of broadcasts, the 64 | organization that transmits the broadcast. 65 | f. "Work" means the literary and/or artistic work offered under the terms 66 | of this License including without limitation any production in the 67 | literary, scientific and artistic domain, whatever may be the mode or 68 | form of its expression including digital form, such as a book, 69 | pamphlet and other writing; a lecture, address, sermon or other work 70 | of the same nature; a dramatic or dramatico-musical work; a 71 | choreographic work or entertainment in dumb show; a musical 72 | composition with or without words; a cinematographic work to which are 73 | assimilated works expressed by a process analogous to cinematography; 74 | a work of drawing, painting, architecture, sculpture, engraving or 75 | lithography; a photographic work to which are assimilated works 76 | expressed by a process analogous to photography; a work of applied 77 | art; an illustration, map, plan, sketch or three-dimensional work 78 | relative to geography, topography, architecture or science; a 79 | performance; a broadcast; a phonogram; a compilation of data to the 80 | extent it is protected as a copyrightable work; or a work performed by 81 | a variety or circus performer to the extent it is not otherwise 82 | considered a literary or artistic work. 83 | g. "You" means an individual or entity exercising rights under this 84 | License who has not previously violated the terms of this License with 85 | respect to the Work, or who has received express permission from the 86 | Licensor to exercise rights under this License despite a previous 87 | violation. 88 | h. "Publicly Perform" means to perform public recitations of the Work and 89 | to communicate to the public those public recitations, by any means or 90 | process, including by wire or wireless means or public digital 91 | performances; to make available to the public Works in such a way that 92 | members of the public may access these Works from a place and at a 93 | place individually chosen by them; to perform the Work to the public 94 | by any means or process and the communication to the public of the 95 | performances of the Work, including by public digital performance; to 96 | broadcast and rebroadcast the Work by any means including signs, 97 | sounds or images. 98 | i. "Reproduce" means to make copies of the Work by any means including 99 | without limitation by sound or visual recordings and the right of 100 | fixation and reproducing fixations of the Work, including storage of a 101 | protected performance or phonogram in digital form or other electronic 102 | medium. 103 | 104 | 2. Fair Dealing Rights. Nothing in this License is intended to reduce, 105 | limit, or restrict any uses free from copyright or rights arising from 106 | limitations or exceptions that are provided for in connection with the 107 | copyright protection under copyright law or other applicable laws. 108 | 109 | 3. License Grant. Subject to the terms and conditions of this License, 110 | Licensor hereby grants You a worldwide, royalty-free, non-exclusive, 111 | perpetual (for the duration of the applicable copyright) license to 112 | exercise the rights in the Work as stated below: 113 | 114 | a. to Reproduce the Work, to incorporate the Work into one or more 115 | Collections, and to Reproduce the Work as incorporated in the 116 | Collections; 117 | b. to create and Reproduce Adaptations provided that any such Adaptation, 118 | including any translation in any medium, takes reasonable steps to 119 | clearly label, demarcate or otherwise identify that changes were made 120 | to the original Work. For example, a translation could be marked "The 121 | original work was translated from English to Spanish," or a 122 | modification could indicate "The original work has been modified."; 123 | c. to Distribute and Publicly Perform the Work including as incorporated 124 | in Collections; and, 125 | d. to Distribute and Publicly Perform Adaptations. 126 | e. For the avoidance of doubt: 127 | 128 | i. Non-waivable Compulsory License Schemes. In those jurisdictions in 129 | which the right to collect royalties through any statutory or 130 | compulsory licensing scheme cannot be waived, the Licensor 131 | reserves the exclusive right to collect such royalties for any 132 | exercise by You of the rights granted under this License; 133 | ii. Waivable Compulsory License Schemes. In those jurisdictions in 134 | which the right to collect royalties through any statutory or 135 | compulsory licensing scheme can be waived, the Licensor waives the 136 | exclusive right to collect such royalties for any exercise by You 137 | of the rights granted under this License; and, 138 | iii. Voluntary License Schemes. The Licensor waives the right to 139 | collect royalties, whether individually or, in the event that the 140 | Licensor is a member of a collecting society that administers 141 | voluntary licensing schemes, via that society, from any exercise 142 | by You of the rights granted under this License. 143 | 144 | The above rights may be exercised in all media and formats whether now 145 | known or hereafter devised. The above rights include the right to make 146 | such modifications as are technically necessary to exercise the rights in 147 | other media and formats. Subject to Section 8(f), all rights not expressly 148 | granted by Licensor are hereby reserved. 149 | 150 | 4. Restrictions. The license granted in Section 3 above is expressly made 151 | subject to and limited by the following restrictions: 152 | 153 | a. You may Distribute or Publicly Perform the Work only under the terms 154 | of this License. You must include a copy of, or the Uniform Resource 155 | Identifier (URI) for, this License with every copy of the Work You 156 | Distribute or Publicly Perform. You may not offer or impose any terms 157 | on the Work that restrict the terms of this License or the ability of 158 | the recipient of the Work to exercise the rights granted to that 159 | recipient under the terms of the License. You may not sublicense the 160 | Work. You must keep intact all notices that refer to this License and 161 | to the disclaimer of warranties with every copy of the Work You 162 | Distribute or Publicly Perform. When You Distribute or Publicly 163 | Perform the Work, You may not impose any effective technological 164 | measures on the Work that restrict the ability of a recipient of the 165 | Work from You to exercise the rights granted to that recipient under 166 | the terms of the License. This Section 4(a) applies to the Work as 167 | incorporated in a Collection, but this does not require the Collection 168 | apart from the Work itself to be made subject to the terms of this 169 | License. If You create a Collection, upon notice from any Licensor You 170 | must, to the extent practicable, remove from the Collection any credit 171 | as required by Section 4(b), as requested. If You create an 172 | Adaptation, upon notice from any Licensor You must, to the extent 173 | practicable, remove from the Adaptation any credit as required by 174 | Section 4(b), as requested. 175 | b. If You Distribute, or Publicly Perform the Work or any Adaptations or 176 | Collections, You must, unless a request has been made pursuant to 177 | Section 4(a), keep intact all copyright notices for the Work and 178 | provide, reasonable to the medium or means You are utilizing: (i) the 179 | name of the Original Author (or pseudonym, if applicable) if supplied, 180 | and/or if the Original Author and/or Licensor designate another party 181 | or parties (e.g., a sponsor institute, publishing entity, journal) for 182 | attribution ("Attribution Parties") in Licensor's copyright notice, 183 | terms of service or by other reasonable means, the name of such party 184 | or parties; (ii) the title of the Work if supplied; (iii) to the 185 | extent reasonably practicable, the URI, if any, that Licensor 186 | specifies to be associated with the Work, unless such URI does not 187 | refer to the copyright notice or licensing information for the Work; 188 | and (iv) , consistent with Section 3(b), in the case of an Adaptation, 189 | a credit identifying the use of the Work in the Adaptation (e.g., 190 | "French translation of the Work by Original Author," or "Screenplay 191 | based on original Work by Original Author"). The credit required by 192 | this Section 4 (b) may be implemented in any reasonable manner; 193 | provided, however, that in the case of a Adaptation or Collection, at 194 | a minimum such credit will appear, if a credit for all contributing 195 | authors of the Adaptation or Collection appears, then as part of these 196 | credits and in a manner at least as prominent as the credits for the 197 | other contributing authors. For the avoidance of doubt, You may only 198 | use the credit required by this Section for the purpose of attribution 199 | in the manner set out above and, by exercising Your rights under this 200 | License, You may not implicitly or explicitly assert or imply any 201 | connection with, sponsorship or endorsement by the Original Author, 202 | Licensor and/or Attribution Parties, as appropriate, of You or Your 203 | use of the Work, without the separate, express prior written 204 | permission of the Original Author, Licensor and/or Attribution 205 | Parties. 206 | c. Except as otherwise agreed in writing by the Licensor or as may be 207 | otherwise permitted by applicable law, if You Reproduce, Distribute or 208 | Publicly Perform the Work either by itself or as part of any 209 | Adaptations or Collections, You must not distort, mutilate, modify or 210 | take other derogatory action in relation to the Work which would be 211 | prejudicial to the Original Author's honor or reputation. Licensor 212 | agrees that in those jurisdictions (e.g. Japan), in which any exercise 213 | of the right granted in Section 3(b) of this License (the right to 214 | make Adaptations) would be deemed to be a distortion, mutilation, 215 | modification or other derogatory action prejudicial to the Original 216 | Author's honor and reputation, the Licensor will waive or not assert, 217 | as appropriate, this Section, to the fullest extent permitted by the 218 | applicable national law, to enable You to reasonably exercise Your 219 | right under Section 3(b) of this License (right to make Adaptations) 220 | but not otherwise. 221 | 222 | 5. Representations, Warranties and Disclaimer 223 | 224 | UNLESS OTHERWISE MUTUALLY AGREED TO BY THE PARTIES IN WRITING, LICENSOR 225 | OFFERS THE WORK AS-IS AND MAKES NO REPRESENTATIONS OR WARRANTIES OF ANY 226 | KIND CONCERNING THE WORK, EXPRESS, IMPLIED, STATUTORY OR OTHERWISE, 227 | INCLUDING, WITHOUT LIMITATION, WARRANTIES OF TITLE, MERCHANTIBILITY, 228 | FITNESS FOR A PARTICULAR PURPOSE, NONINFRINGEMENT, OR THE ABSENCE OF 229 | LATENT OR OTHER DEFECTS, ACCURACY, OR THE PRESENCE OF ABSENCE OF ERRORS, 230 | WHETHER OR NOT DISCOVERABLE. SOME JURISDICTIONS DO NOT ALLOW THE EXCLUSION 231 | OF IMPLIED WARRANTIES, SO SUCH EXCLUSION MAY NOT APPLY TO YOU. 232 | 233 | 6. Limitation on Liability. EXCEPT TO THE EXTENT REQUIRED BY APPLICABLE 234 | LAW, IN NO EVENT WILL LICENSOR BE LIABLE TO YOU ON ANY LEGAL THEORY FOR 235 | ANY SPECIAL, INCIDENTAL, CONSEQUENTIAL, PUNITIVE OR EXEMPLARY DAMAGES 236 | ARISING OUT OF THIS LICENSE OR THE USE OF THE WORK, EVEN IF LICENSOR HAS 237 | BEEN ADVISED OF THE POSSIBILITY OF SUCH DAMAGES. 238 | 239 | 7. Termination 240 | 241 | a. This License and the rights granted hereunder will terminate 242 | automatically upon any breach by You of the terms of this License. 243 | Individuals or entities who have received Adaptations or Collections 244 | from You under this License, however, will not have their licenses 245 | terminated provided such individuals or entities remain in full 246 | compliance with those licenses. Sections 1, 2, 5, 6, 7, and 8 will 247 | survive any termination of this License. 248 | b. Subject to the above terms and conditions, the license granted here is 249 | perpetual (for the duration of the applicable copyright in the Work). 250 | Notwithstanding the above, Licensor reserves the right to release the 251 | Work under different license terms or to stop distributing the Work at 252 | any time; provided, however that any such election will not serve to 253 | withdraw this License (or any other license that has been, or is 254 | required to be, granted under the terms of this License), and this 255 | License will continue in full force and effect unless terminated as 256 | stated above. 257 | 258 | 8. Miscellaneous 259 | 260 | a. Each time You Distribute or Publicly Perform the Work or a Collection, 261 | the Licensor offers to the recipient a license to the Work on the same 262 | terms and conditions as the license granted to You under this License. 263 | b. Each time You Distribute or Publicly Perform an Adaptation, Licensor 264 | offers to the recipient a license to the original Work on the same 265 | terms and conditions as the license granted to You under this License. 266 | c. If any provision of this License is invalid or unenforceable under 267 | applicable law, it shall not affect the validity or enforceability of 268 | the remainder of the terms of this License, and without further action 269 | by the parties to this agreement, such provision shall be reformed to 270 | the minimum extent necessary to make such provision valid and 271 | enforceable. 272 | d. No term or provision of this License shall be deemed waived and no 273 | breach consented to unless such waiver or consent shall be in writing 274 | and signed by the party to be charged with such waiver or consent. 275 | e. This License constitutes the entire agreement between the parties with 276 | respect to the Work licensed here. There are no understandings, 277 | agreements or representations with respect to the Work not specified 278 | here. Licensor shall not be bound by any additional provisions that 279 | may appear in any communication from You. This License may not be 280 | modified without the mutual written agreement of the Licensor and You. 281 | f. The rights granted under, and the subject matter referenced, in this 282 | License were drafted utilizing the terminology of the Berne Convention 283 | for the Protection of Literary and Artistic Works (as amended on 284 | September 28, 1979), the Rome Convention of 1961, the WIPO Copyright 285 | Treaty of 1996, the WIPO Performances and Phonograms Treaty of 1996 286 | and the Universal Copyright Convention (as revised on July 24, 1971). 287 | These rights and subject matter take effect in the relevant 288 | jurisdiction in which the License terms are sought to be enforced 289 | according to the corresponding provisions of the implementation of 290 | those treaty provisions in the applicable national law. If the 291 | standard suite of rights granted under applicable copyright law 292 | includes additional rights not granted under this License, such 293 | additional rights are deemed to be included in the License; this 294 | License is not intended to restrict the license of any rights under 295 | applicable law. 296 | 297 | 298 | Creative Commons Notice 299 | 300 | Creative Commons is not a party to this License, and makes no warranty 301 | whatsoever in connection with the Work. Creative Commons will not be 302 | liable to You or any party on any legal theory for any damages 303 | whatsoever, including without limitation any general, special, 304 | incidental or consequential damages arising in connection to this 305 | license. Notwithstanding the foregoing two (2) sentences, if Creative 306 | Commons has expressly identified itself as the Licensor hereunder, it 307 | shall have all rights and obligations of Licensor. 308 | 309 | Except for the limited purpose of indicating to the public that the 310 | Work is licensed under the CCPL, Creative Commons does not authorize 311 | the use by either party of the trademark "Creative Commons" or any 312 | related trademark or logo of Creative Commons without the prior 313 | written consent of Creative Commons. Any permitted use will be in 314 | compliance with Creative Commons' then-current trademark usage 315 | guidelines, as may be published on its website or otherwise made 316 | available upon request from time to time. For the avoidance of doubt, 317 | this trademark restriction does not form part of this License. 318 | 319 | Creative Commons may be contacted at https://creativecommons.org/. 320 | -------------------------------------------------------------------------------- /LED_DRIVER/res/eagle/led_driver.brd: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | 27 | 28 | 29 | 30 | 31 | 32 | 33 | 34 | 35 | 36 | 37 | 38 | 39 | 40 | 41 | 42 | 43 | 44 | 45 | 46 | 47 | 48 | 49 | 50 | 51 | 52 | 53 | 54 | 55 | 56 | 57 | 58 | 59 | 60 | 61 | 62 | 63 | 64 | 65 | 66 | 67 | 68 | 69 | 70 | 71 | 72 | 73 | 74 | 75 | 76 | 77 | 78 | 79 | 80 | 81 | 82 | 83 | 84 | 85 | 86 | 87 | 88 | 89 | 90 | 91 | 92 | 93 | 94 | 95 | 96 | 97 | 98 | 99 | 100 | 101 | 102 | 103 | 104 | 105 | 106 | 107 | 108 | 109 | 110 | 111 | 112 | 113 | 114 | 115 | 116 | 117 | 118 | 119 | 120 | 121 | 122 | 123 | 124 | 125 | 126 | 127 | 128 | 129 | 130 | 131 | 132 | 133 | 134 | 135 | 136 | 137 | 138 | 139 | 140 | 141 | 142 | 143 | 144 | 145 | 146 | 147 | 148 | 149 | 150 | 151 | 152 | 153 | 154 | 155 | 156 | 157 | 158 | 159 | 160 | 161 | 162 | 163 | 164 | 165 | 166 | 167 | 168 | 169 | 170 | 171 | 172 | 173 | 174 | 175 | 176 | 177 | 178 | 179 | 180 | 181 | 182 | 183 | 184 | 185 | 186 | 187 | 188 | 189 | 190 | 191 | 192 | 193 | 194 | 195 | 196 | 197 | 198 | 199 | 200 | 201 | 202 | 203 | 204 | 205 | 206 | 207 | 208 | 209 | 210 | 211 | 212 | 213 | 214 | 215 | 216 | 217 | 218 | 219 | 220 | 221 | 222 | 223 | 224 | 225 | 226 | 227 | 228 | 229 | 230 | 231 | 232 | 233 | 234 | 235 | 236 | 237 | 238 | 239 | 240 | 241 | 242 | 243 | 244 | 245 | 246 | 247 | + 248 | + 249 | + 250 | + 251 | LED driver 252 | board 253 | VCC 254 | GND 255 | ATtiny85 256 | platis.solutions 257 | 258 | 259 | 260 | <h3>SparkFun Electronics' preferred foot prints</h3> 261 | In this library you'll find all manner of digital ICs- microcontrollers, memory chips, logic chips, FPGAs, etc.<br><br> 262 | We've spent an enormous amount of time creating and checking these footprints and parts, but it is the end user's responsibility to ensure correctness and suitablity for a given componet or application. If you enjoy using this library, please buy one of our products at www.sparkfun.com. 263 | <br><br> 264 | <b>Licensing:</b> Creative Commons ShareAlike 4.0 International - https://creativecommons.org/licenses/by-sa/4.0/ 265 | <br><br> 266 | You are welcome to use this library for commercial purposes. For attribution, we ask that when you begin to sell your device using our footprint, you email us with a link to the product being sold. We want bragging rights that we helped (in a very small part) to create your 8th world wonder. We would like the opportunity to feature your device on our homepage. 267 | 268 | 269 | <b>Dual In Line</b> 270 | 271 | 272 | 273 | 274 | 275 | 276 | 277 | 278 | 279 | 280 | 281 | 282 | 283 | 284 | 285 | >VALUE 286 | >NAME 287 | 288 | 289 | 290 | 291 | <b>Wago Screw Clamps</b><p> 292 | Grid 5.00 mm<p> 293 | <author>Created by librarian@cadsoft.de</author> 294 | 295 | 296 | <b>WAGO SCREW CLAMP</b> 297 | 298 | 299 | 300 | 301 | 302 | 303 | 304 | 305 | 306 | 307 | 308 | 309 | 310 | 311 | 312 | 313 | 314 | 315 | 316 | 317 | 318 | 319 | >VALUE 320 | >NAME 321 | 1 322 | 2 323 | 324 | 325 | 326 | 327 | <h3>SparkFun Electronics' preferred foot prints</h3> 328 | In this library you'll find discrete semiconductors- transistors, diodes, TRIACs, optoisolators, etc.<br><br> 329 | We've spent an enormous amount of time creating and checking these footprints and parts, but it is the end user's responsibility to ensure correctness and suitablity for a given componet or application. If you enjoy using this library, please buy one of our products at www.sparkfun.com. 330 | <br><br> 331 | <b>Licensing:</b> Creative Commons ShareAlike 4.0 International - https://creativecommons.org/licenses/by-sa/4.0/ 332 | <br><br> 333 | You are welcome to use this library for commercial purposes. For attribution, we ask that when you begin to sell your device using our footprint, you email us with a link to the product being sold. We want bragging rights that we helped (in a very small part) to create your 8th world wonder. We would like the opportunity to feature your device on our homepage. 334 | 335 | 336 | 337 | 338 | 339 | 340 | 341 | 342 | 343 | 344 | 345 | >NAME 346 | >VALUE 347 | 348 | 349 | 350 | 351 | <h3>SparkFun Electronics' preferred foot prints</h3> 352 | In this library you'll find resistors, capacitors, inductors, test points, jumper pads, etc.<br><br> 353 | We've spent an enormous amount of time creating and checking these footprints and parts, but it is the end user's responsibility to ensure correctness and suitablity for a given componet or application. If you enjoy using this library, please buy one of our products at www.sparkfun.com. 354 | <br><br> 355 | <b>Licensing:</b> Creative Commons ShareAlike 4.0 International - https://creativecommons.org/licenses/by-sa/4.0/ 356 | <br><br> 357 | You are welcome to use this library for commercial purposes. For attribution, we ask that when you begin to sell your device using our footprint, you email us with a link to the product being sold. We want bragging rights that we helped (in a very small part) to create your 8th world wonder. We would like the opportunity to feature your device on our homepage. 358 | 359 | 360 | 361 | 362 | 363 | 364 | 365 | 366 | 367 | 368 | 369 | 370 | >Name 371 | >Value 372 | 373 | 374 | 375 | 376 | <h3>SparkFun Electronics' preferred foot prints</h3> 377 | In this library you'll find non-functional items- supply symbols, logos, notations, frame blocks, etc.<br><br> 378 | We've spent an enormous amount of time creating and checking these footprints and parts, but it is the end user's responsibility to ensure correctness and suitablity for a given componet or application. If you enjoy using this library, please buy one of our products at www.sparkfun.com. 379 | <br><br> 380 | <b>Licensing:</b> Creative Commons ShareAlike 4.0 International - https://creativecommons.org/licenses/by-sa/4.0/ 381 | <br><br> 382 | You are welcome to use this library for commercial purposes. For attribution, we ask that when you begin to sell your device using our footprint, you email us with a link to the product being sold. We want bragging rights that we helped (in a very small part) to create your 8th world wonder. We would like the opportunity to feature your device on our homepage. 383 | 384 | 385 | 386 | 387 | 388 | 389 | 390 | 391 | 392 | 393 | 394 | 395 | 396 | 397 | 398 | 399 | 400 | 401 | 402 | 403 | 404 | 405 | 406 | 407 | 408 | 409 | 410 | 411 | 412 | 413 | 414 | 415 | 416 | 417 | 418 | 419 | 420 | 421 | 422 | 423 | 424 | 425 | 426 | 427 | 428 | 429 | 430 | 431 | 432 | 433 | <b>EAGLE Design Rules</b> 434 | <p> 435 | Die Standard-Design-Rules sind so gewählt, dass sie für 436 | die meisten Anwendungen passen. Sollte ihre Platine 437 | besondere Anforderungen haben, treffen Sie die erforderlichen 438 | Einstellungen hier und speichern die Design Rules unter 439 | einem neuen Namen ab. 440 | <b>Laen's PCB Order Design Rules</b> 441 | <p> 442 | Please make sure your boards conform to these design rules. 443 | 444 | 445 | 446 | 447 | 448 | 449 | 450 | 451 | 452 | 453 | 454 | 455 | 456 | 457 | 458 | 459 | 460 | 461 | 462 | 463 | 464 | 465 | 466 | 467 | 468 | 469 | 470 | 471 | 472 | 473 | 474 | 475 | 476 | 477 | 478 | 479 | 480 | 481 | 482 | 483 | 484 | 485 | 486 | 487 | 488 | 489 | 490 | 491 | 492 | 493 | 494 | 495 | 496 | 497 | 498 | 499 | 500 | 501 | 502 | 503 | 504 | 505 | 506 | 507 | 508 | 509 | 510 | 511 | 512 | 513 | 514 | 515 | 516 | 517 | 518 | 519 | 520 | 521 | 522 | 523 | 524 | 525 | 526 | 527 | 528 | 529 | 530 | 531 | 532 | 533 | 534 | 535 | 536 | 537 | 538 | 539 | 540 | 541 | 542 | 543 | 544 | 545 | 546 | 547 | 548 | 549 | 550 | 551 | 552 | 553 | 554 | 555 | 556 | 557 | 558 | 559 | 560 | 561 | 562 | 563 | 564 | 565 | 566 | 567 | 568 | 569 | 570 | 571 | 572 | 573 | 574 | 575 | 576 | 577 | 578 | 579 | 580 | 581 | 582 | 583 | 584 | 585 | 586 | 587 | 588 | 589 | 590 | 591 | 592 | 593 | 594 | 595 | 596 | 597 | 598 | 599 | 600 | 601 | 602 | 603 | 604 | 605 | 606 | 607 | 608 | 609 | 610 | 611 | 612 | 613 | 614 | 615 | 616 | 617 | 618 | 619 | 620 | 621 | 622 | 623 | 624 | 625 | 626 | 627 | 628 | 629 | 630 | 631 | 632 | 633 | 634 | 635 | 636 | 637 | 638 | 639 | 640 | 641 | 642 | 643 | 644 | 645 | 646 | 647 | 648 | 649 | 650 | 651 | 652 | 653 | 654 | 655 | 656 | 657 | 658 | 659 | 660 | 661 | 662 | 663 | 664 | 665 | 666 | 667 | 668 | 669 | 670 | 671 | 672 | 673 | 674 | 675 | 676 | 677 | 678 | 679 | 680 | 681 | 682 | 683 | 684 | 685 | 686 | 687 | 688 | 689 | 690 | 691 | 692 | 693 | 694 | 695 | 696 | 697 | 698 | 699 | 700 | 701 | 702 | 703 | 704 | 705 | 706 | 707 | 708 | 709 | 710 | 711 | 712 | 713 | 714 | 715 | 716 | 717 | 718 | 719 | 720 | 721 | 722 | 723 | 724 | 725 | 726 | 727 | 728 | 729 | 730 | 731 | 732 | 733 | 734 | 735 | 736 | 737 | 738 | 739 | 740 | 741 | 742 | 743 | 744 | 745 | 746 | 747 | 748 | 749 | 750 | 751 | 752 | 753 | 754 | 755 | 756 | 757 | 758 | 759 | 760 | 761 | 762 | 763 | 764 | 765 | 766 | 767 | 768 | 769 | 770 | 771 | 772 | 773 | 774 | 775 | 776 | 777 | 778 | 779 | 780 | 781 | 782 | 783 | 784 | 785 | 786 | 787 | 788 | 789 | 790 | 791 | 792 | 793 | 794 | 795 | 796 | 797 | 798 | 799 | 800 | 801 | 802 | 803 | 804 | 805 | 806 | 807 | 808 | 809 | 810 | 811 | 812 | 813 | 814 | 815 | 816 | 817 | 818 | 819 | 820 | 821 | 822 | 823 | 824 | 825 | 826 | 827 | 828 | 829 | Since Version 6.2.2 text objects can contain more than one line, 830 | which will not be processed correctly with this version. 831 | 832 | 833 | 834 | -------------------------------------------------------------------------------- /LED_DRIVER/res/led_controller_schem.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/platisd/AndroidCar/432ae929092edd4bef92710085009936a9e346c2/LED_DRIVER/res/led_controller_schem.png -------------------------------------------------------------------------------- /LED_DRIVER/res/led_driver_back_render.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/platisd/AndroidCar/432ae929092edd4bef92710085009936a9e346c2/LED_DRIVER/res/led_driver_back_render.png -------------------------------------------------------------------------------- /LED_DRIVER/res/led_driver_front_render.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/platisd/AndroidCar/432ae929092edd4bef92710085009936a9e346c2/LED_DRIVER/res/led_driver_front_render.png -------------------------------------------------------------------------------- /LED_DRIVER/variables.h: -------------------------------------------------------------------------------- 1 | #ifndef led_vars_h 2 | #define led_vars_h 3 | 4 | enum State { 5 | RIGHT, 6 | STOP, 7 | MOVING_STRAIGHT, 8 | LEFT, 9 | RC 10 | }; 11 | 12 | #define RX_PIN 2 13 | #define UNUSED_TX_PIN 3 14 | 15 | #endif 16 | -------------------------------------------------------------------------------- /LICENSE: -------------------------------------------------------------------------------- 1 | GNU GENERAL PUBLIC LICENSE 2 | Version 3, 29 June 2007 3 | 4 | Copyright (C) 2007 Free Software Foundation, Inc. 5 | Everyone is permitted to copy and distribute verbatim copies 6 | of this license document, but changing it is not allowed. 7 | 8 | Preamble 9 | 10 | The GNU General Public License is a free, copyleft license for 11 | software and other kinds of works. 12 | 13 | The licenses for most software and other practical works are designed 14 | to take away your freedom to share and change the works. By contrast, 15 | the GNU General Public License is intended to guarantee your freedom to 16 | share and change all versions of a program--to make sure it remains free 17 | software for all its users. We, the Free Software Foundation, use the 18 | GNU General Public License for most of our software; it applies also to 19 | any other work released this way by its authors. You can apply it to 20 | your programs, too. 21 | 22 | When we speak of free software, we are referring to freedom, not 23 | price. Our General Public Licenses are designed to make sure that you 24 | have the freedom to distribute copies of free software (and charge for 25 | them if you wish), that you receive source code or can get it if you 26 | want it, that you can change the software or use pieces of it in new 27 | free programs, and that you know you can do these things. 28 | 29 | To protect your rights, we need to prevent others from denying you 30 | these rights or asking you to surrender the rights. Therefore, you have 31 | certain responsibilities if you distribute copies of the software, or if 32 | you modify it: responsibilities to respect the freedom of others. 33 | 34 | For example, if you distribute copies of such a program, whether 35 | gratis or for a fee, you must pass on to the recipients the same 36 | freedoms that you received. You must make sure that they, too, receive 37 | or can get the source code. And you must show them these terms so they 38 | know their rights. 39 | 40 | Developers that use the GNU GPL protect your rights with two steps: 41 | (1) assert copyright on the software, and (2) offer you this License 42 | giving you legal permission to copy, distribute and/or modify it. 43 | 44 | For the developers' and authors' protection, the GPL clearly explains 45 | that there is no warranty for this free software. For both users' and 46 | authors' sake, the GPL requires that modified versions be marked as 47 | changed, so that their problems will not be attributed erroneously to 48 | authors of previous versions. 49 | 50 | Some devices are designed to deny users access to install or run 51 | modified versions of the software inside them, although the manufacturer 52 | can do so. This is fundamentally incompatible with the aim of 53 | protecting users' freedom to change the software. The systematic 54 | pattern of such abuse occurs in the area of products for individuals to 55 | use, which is precisely where it is most unacceptable. Therefore, we 56 | have designed this version of the GPL to prohibit the practice for those 57 | products. If such problems arise substantially in other domains, we 58 | stand ready to extend this provision to those domains in future versions 59 | of the GPL, as needed to protect the freedom of users. 60 | 61 | Finally, every program is threatened constantly by software patents. 62 | States should not allow patents to restrict development and use of 63 | software on general-purpose computers, but in those that do, we wish to 64 | avoid the special danger that patents applied to a free program could 65 | make it effectively proprietary. To prevent this, the GPL assures that 66 | patents cannot be used to render the program non-free. 67 | 68 | The precise terms and conditions for copying, distribution and 69 | modification follow. 70 | 71 | TERMS AND CONDITIONS 72 | 73 | 0. Definitions. 74 | 75 | "This License" refers to version 3 of the GNU General Public License. 76 | 77 | "Copyright" also means copyright-like laws that apply to other kinds of 78 | works, such as semiconductor masks. 79 | 80 | "The Program" refers to any copyrightable work licensed under this 81 | License. Each licensee is addressed as "you". "Licensees" and 82 | "recipients" may be individuals or organizations. 83 | 84 | To "modify" a work means to copy from or adapt all or part of the work 85 | in a fashion requiring copyright permission, other than the making of an 86 | exact copy. The resulting work is called a "modified version" of the 87 | earlier work or a work "based on" the earlier work. 88 | 89 | A "covered work" means either the unmodified Program or a work based 90 | on the Program. 91 | 92 | To "propagate" a work means to do anything with it that, without 93 | permission, would make you directly or secondarily liable for 94 | infringement under applicable copyright law, except executing it on a 95 | computer or modifying a private copy. Propagation includes copying, 96 | distribution (with or without modification), making available to the 97 | public, and in some countries other activities as well. 98 | 99 | To "convey" a work means any kind of propagation that enables other 100 | parties to make or receive copies. Mere interaction with a user through 101 | a computer network, with no transfer of a copy, is not conveying. 102 | 103 | An interactive user interface displays "Appropriate Legal Notices" 104 | to the extent that it includes a convenient and prominently visible 105 | feature that (1) displays an appropriate copyright notice, and (2) 106 | tells the user that there is no warranty for the work (except to the 107 | extent that warranties are provided), that licensees may convey the 108 | work under this License, and how to view a copy of this License. If 109 | the interface presents a list of user commands or options, such as a 110 | menu, a prominent item in the list meets this criterion. 111 | 112 | 1. Source Code. 113 | 114 | The "source code" for a work means the preferred form of the work 115 | for making modifications to it. "Object code" means any non-source 116 | form of a work. 117 | 118 | A "Standard Interface" means an interface that either is an official 119 | standard defined by a recognized standards body, or, in the case of 120 | interfaces specified for a particular programming language, one that 121 | is widely used among developers working in that language. 122 | 123 | The "System Libraries" of an executable work include anything, other 124 | than the work as a whole, that (a) is included in the normal form of 125 | packaging a Major Component, but which is not part of that Major 126 | Component, and (b) serves only to enable use of the work with that 127 | Major Component, or to implement a Standard Interface for which an 128 | implementation is available to the public in source code form. A 129 | "Major Component", in this context, means a major essential component 130 | (kernel, window system, and so on) of the specific operating system 131 | (if any) on which the executable work runs, or a compiler used to 132 | produce the work, or an object code interpreter used to run it. 133 | 134 | The "Corresponding Source" for a work in object code form means all 135 | the source code needed to generate, install, and (for an executable 136 | work) run the object code and to modify the work, including scripts to 137 | control those activities. However, it does not include the work's 138 | System Libraries, or general-purpose tools or generally available free 139 | programs which are used unmodified in performing those activities but 140 | which are not part of the work. For example, Corresponding Source 141 | includes interface definition files associated with source files for 142 | the work, and the source code for shared libraries and dynamically 143 | linked subprograms that the work is specifically designed to require, 144 | such as by intimate data communication or control flow between those 145 | subprograms and other parts of the work. 146 | 147 | The Corresponding Source need not include anything that users 148 | can regenerate automatically from other parts of the Corresponding 149 | Source. 150 | 151 | The Corresponding Source for a work in source code form is that 152 | same work. 153 | 154 | 2. Basic Permissions. 155 | 156 | All rights granted under this License are granted for the term of 157 | copyright on the Program, and are irrevocable provided the stated 158 | conditions are met. This License explicitly affirms your unlimited 159 | permission to run the unmodified Program. The output from running a 160 | covered work is covered by this License only if the output, given its 161 | content, constitutes a covered work. This License acknowledges your 162 | rights of fair use or other equivalent, as provided by copyright law. 163 | 164 | You may make, run and propagate covered works that you do not 165 | convey, without conditions so long as your license otherwise remains 166 | in force. You may convey covered works to others for the sole purpose 167 | of having them make modifications exclusively for you, or provide you 168 | with facilities for running those works, provided that you comply with 169 | the terms of this License in conveying all material for which you do 170 | not control copyright. Those thus making or running the covered works 171 | for you must do so exclusively on your behalf, under your direction 172 | and control, on terms that prohibit them from making any copies of 173 | your copyrighted material outside their relationship with you. 174 | 175 | Conveying under any other circumstances is permitted solely under 176 | the conditions stated below. Sublicensing is not allowed; section 10 177 | makes it unnecessary. 178 | 179 | 3. Protecting Users' Legal Rights From Anti-Circumvention Law. 180 | 181 | No covered work shall be deemed part of an effective technological 182 | measure under any applicable law fulfilling obligations under article 183 | 11 of the WIPO copyright treaty adopted on 20 December 1996, or 184 | similar laws prohibiting or restricting circumvention of such 185 | measures. 186 | 187 | When you convey a covered work, you waive any legal power to forbid 188 | circumvention of technological measures to the extent such circumvention 189 | is effected by exercising rights under this License with respect to 190 | the covered work, and you disclaim any intention to limit operation or 191 | modification of the work as a means of enforcing, against the work's 192 | users, your or third parties' legal rights to forbid circumvention of 193 | technological measures. 194 | 195 | 4. Conveying Verbatim Copies. 196 | 197 | You may convey verbatim copies of the Program's source code as you 198 | receive it, in any medium, provided that you conspicuously and 199 | appropriately publish on each copy an appropriate copyright notice; 200 | keep intact all notices stating that this License and any 201 | non-permissive terms added in accord with section 7 apply to the code; 202 | keep intact all notices of the absence of any warranty; and give all 203 | recipients a copy of this License along with the Program. 204 | 205 | You may charge any price or no price for each copy that you convey, 206 | and you may offer support or warranty protection for a fee. 207 | 208 | 5. Conveying Modified Source Versions. 209 | 210 | You may convey a work based on the Program, or the modifications to 211 | produce it from the Program, in the form of source code under the 212 | terms of section 4, provided that you also meet all of these conditions: 213 | 214 | a) The work must carry prominent notices stating that you modified 215 | it, and giving a relevant date. 216 | 217 | b) The work must carry prominent notices stating that it is 218 | released under this License and any conditions added under section 219 | 7. This requirement modifies the requirement in section 4 to 220 | "keep intact all notices". 221 | 222 | c) You must license the entire work, as a whole, under this 223 | License to anyone who comes into possession of a copy. This 224 | License will therefore apply, along with any applicable section 7 225 | additional terms, to the whole of the work, and all its parts, 226 | regardless of how they are packaged. This License gives no 227 | permission to license the work in any other way, but it does not 228 | invalidate such permission if you have separately received it. 229 | 230 | d) If the work has interactive user interfaces, each must display 231 | Appropriate Legal Notices; however, if the Program has interactive 232 | interfaces that do not display Appropriate Legal Notices, your 233 | work need not make them do so. 234 | 235 | A compilation of a covered work with other separate and independent 236 | works, which are not by their nature extensions of the covered work, 237 | and which are not combined with it such as to form a larger program, 238 | in or on a volume of a storage or distribution medium, is called an 239 | "aggregate" if the compilation and its resulting copyright are not 240 | used to limit the access or legal rights of the compilation's users 241 | beyond what the individual works permit. Inclusion of a covered work 242 | in an aggregate does not cause this License to apply to the other 243 | parts of the aggregate. 244 | 245 | 6. Conveying Non-Source Forms. 246 | 247 | You may convey a covered work in object code form under the terms 248 | of sections 4 and 5, provided that you also convey the 249 | machine-readable Corresponding Source under the terms of this License, 250 | in one of these ways: 251 | 252 | a) Convey the object code in, or embodied in, a physical product 253 | (including a physical distribution medium), accompanied by the 254 | Corresponding Source fixed on a durable physical medium 255 | customarily used for software interchange. 256 | 257 | b) Convey the object code in, or embodied in, a physical product 258 | (including a physical distribution medium), accompanied by a 259 | written offer, valid for at least three years and valid for as 260 | long as you offer spare parts or customer support for that product 261 | model, to give anyone who possesses the object code either (1) a 262 | copy of the Corresponding Source for all the software in the 263 | product that is covered by this License, on a durable physical 264 | medium customarily used for software interchange, for a price no 265 | more than your reasonable cost of physically performing this 266 | conveying of source, or (2) access to copy the 267 | Corresponding Source from a network server at no charge. 268 | 269 | c) Convey individual copies of the object code with a copy of the 270 | written offer to provide the Corresponding Source. This 271 | alternative is allowed only occasionally and noncommercially, and 272 | only if you received the object code with such an offer, in accord 273 | with subsection 6b. 274 | 275 | d) Convey the object code by offering access from a designated 276 | place (gratis or for a charge), and offer equivalent access to the 277 | Corresponding Source in the same way through the same place at no 278 | further charge. You need not require recipients to copy the 279 | Corresponding Source along with the object code. If the place to 280 | copy the object code is a network server, the Corresponding Source 281 | may be on a different server (operated by you or a third party) 282 | that supports equivalent copying facilities, provided you maintain 283 | clear directions next to the object code saying where to find the 284 | Corresponding Source. Regardless of what server hosts the 285 | Corresponding Source, you remain obligated to ensure that it is 286 | available for as long as needed to satisfy these requirements. 287 | 288 | e) Convey the object code using peer-to-peer transmission, provided 289 | you inform other peers where the object code and Corresponding 290 | Source of the work are being offered to the general public at no 291 | charge under subsection 6d. 292 | 293 | A separable portion of the object code, whose source code is excluded 294 | from the Corresponding Source as a System Library, need not be 295 | included in conveying the object code work. 296 | 297 | A "User Product" is either (1) a "consumer product", which means any 298 | tangible personal property which is normally used for personal, family, 299 | or household purposes, or (2) anything designed or sold for incorporation 300 | into a dwelling. In determining whether a product is a consumer product, 301 | doubtful cases shall be resolved in favor of coverage. For a particular 302 | product received by a particular user, "normally used" refers to a 303 | typical or common use of that class of product, regardless of the status 304 | of the particular user or of the way in which the particular user 305 | actually uses, or expects or is expected to use, the product. A product 306 | is a consumer product regardless of whether the product has substantial 307 | commercial, industrial or non-consumer uses, unless such uses represent 308 | the only significant mode of use of the product. 309 | 310 | "Installation Information" for a User Product means any methods, 311 | procedures, authorization keys, or other information required to install 312 | and execute modified versions of a covered work in that User Product from 313 | a modified version of its Corresponding Source. The information must 314 | suffice to ensure that the continued functioning of the modified object 315 | code is in no case prevented or interfered with solely because 316 | modification has been made. 317 | 318 | If you convey an object code work under this section in, or with, or 319 | specifically for use in, a User Product, and the conveying occurs as 320 | part of a transaction in which the right of possession and use of the 321 | User Product is transferred to the recipient in perpetuity or for a 322 | fixed term (regardless of how the transaction is characterized), the 323 | Corresponding Source conveyed under this section must be accompanied 324 | by the Installation Information. But this requirement does not apply 325 | if neither you nor any third party retains the ability to install 326 | modified object code on the User Product (for example, the work has 327 | been installed in ROM). 328 | 329 | The requirement to provide Installation Information does not include a 330 | requirement to continue to provide support service, warranty, or updates 331 | for a work that has been modified or installed by the recipient, or for 332 | the User Product in which it has been modified or installed. Access to a 333 | network may be denied when the modification itself materially and 334 | adversely affects the operation of the network or violates the rules and 335 | protocols for communication across the network. 336 | 337 | Corresponding Source conveyed, and Installation Information provided, 338 | in accord with this section must be in a format that is publicly 339 | documented (and with an implementation available to the public in 340 | source code form), and must require no special password or key for 341 | unpacking, reading or copying. 342 | 343 | 7. Additional Terms. 344 | 345 | "Additional permissions" are terms that supplement the terms of this 346 | License by making exceptions from one or more of its conditions. 347 | Additional permissions that are applicable to the entire Program shall 348 | be treated as though they were included in this License, to the extent 349 | that they are valid under applicable law. If additional permissions 350 | apply only to part of the Program, that part may be used separately 351 | under those permissions, but the entire Program remains governed by 352 | this License without regard to the additional permissions. 353 | 354 | When you convey a copy of a covered work, you may at your option 355 | remove any additional permissions from that copy, or from any part of 356 | it. (Additional permissions may be written to require their own 357 | removal in certain cases when you modify the work.) You may place 358 | additional permissions on material, added by you to a covered work, 359 | for which you have or can give appropriate copyright permission. 360 | 361 | Notwithstanding any other provision of this License, for material you 362 | add to a covered work, you may (if authorized by the copyright holders of 363 | that material) supplement the terms of this License with terms: 364 | 365 | a) Disclaiming warranty or limiting liability differently from the 366 | terms of sections 15 and 16 of this License; or 367 | 368 | b) Requiring preservation of specified reasonable legal notices or 369 | author attributions in that material or in the Appropriate Legal 370 | Notices displayed by works containing it; or 371 | 372 | c) Prohibiting misrepresentation of the origin of that material, or 373 | requiring that modified versions of such material be marked in 374 | reasonable ways as different from the original version; or 375 | 376 | d) Limiting the use for publicity purposes of names of licensors or 377 | authors of the material; or 378 | 379 | e) Declining to grant rights under trademark law for use of some 380 | trade names, trademarks, or service marks; or 381 | 382 | f) Requiring indemnification of licensors and authors of that 383 | material by anyone who conveys the material (or modified versions of 384 | it) with contractual assumptions of liability to the recipient, for 385 | any liability that these contractual assumptions directly impose on 386 | those licensors and authors. 387 | 388 | All other non-permissive additional terms are considered "further 389 | restrictions" within the meaning of section 10. If the Program as you 390 | received it, or any part of it, contains a notice stating that it is 391 | governed by this License along with a term that is a further 392 | restriction, you may remove that term. If a license document contains 393 | a further restriction but permits relicensing or conveying under this 394 | License, you may add to a covered work material governed by the terms 395 | of that license document, provided that the further restriction does 396 | not survive such relicensing or conveying. 397 | 398 | If you add terms to a covered work in accord with this section, you 399 | must place, in the relevant source files, a statement of the 400 | additional terms that apply to those files, or a notice indicating 401 | where to find the applicable terms. 402 | 403 | Additional terms, permissive or non-permissive, may be stated in the 404 | form of a separately written license, or stated as exceptions; 405 | the above requirements apply either way. 406 | 407 | 8. Termination. 408 | 409 | You may not propagate or modify a covered work except as expressly 410 | provided under this License. Any attempt otherwise to propagate or 411 | modify it is void, and will automatically terminate your rights under 412 | this License (including any patent licenses granted under the third 413 | paragraph of section 11). 414 | 415 | However, if you cease all violation of this License, then your 416 | license from a particular copyright holder is reinstated (a) 417 | provisionally, unless and until the copyright holder explicitly and 418 | finally terminates your license, and (b) permanently, if the copyright 419 | holder fails to notify you of the violation by some reasonable means 420 | prior to 60 days after the cessation. 421 | 422 | Moreover, your license from a particular copyright holder is 423 | reinstated permanently if the copyright holder notifies you of the 424 | violation by some reasonable means, this is the first time you have 425 | received notice of violation of this License (for any work) from that 426 | copyright holder, and you cure the violation prior to 30 days after 427 | your receipt of the notice. 428 | 429 | Termination of your rights under this section does not terminate the 430 | licenses of parties who have received copies or rights from you under 431 | this License. If your rights have been terminated and not permanently 432 | reinstated, you do not qualify to receive new licenses for the same 433 | material under section 10. 434 | 435 | 9. Acceptance Not Required for Having Copies. 436 | 437 | You are not required to accept this License in order to receive or 438 | run a copy of the Program. Ancillary propagation of a covered work 439 | occurring solely as a consequence of using peer-to-peer transmission 440 | to receive a copy likewise does not require acceptance. However, 441 | nothing other than this License grants you permission to propagate or 442 | modify any covered work. These actions infringe copyright if you do 443 | not accept this License. Therefore, by modifying or propagating a 444 | covered work, you indicate your acceptance of this License to do so. 445 | 446 | 10. Automatic Licensing of Downstream Recipients. 447 | 448 | Each time you convey a covered work, the recipient automatically 449 | receives a license from the original licensors, to run, modify and 450 | propagate that work, subject to this License. You are not responsible 451 | for enforcing compliance by third parties with this License. 452 | 453 | An "entity transaction" is a transaction transferring control of an 454 | organization, or substantially all assets of one, or subdividing an 455 | organization, or merging organizations. If propagation of a covered 456 | work results from an entity transaction, each party to that 457 | transaction who receives a copy of the work also receives whatever 458 | licenses to the work the party's predecessor in interest had or could 459 | give under the previous paragraph, plus a right to possession of the 460 | Corresponding Source of the work from the predecessor in interest, if 461 | the predecessor has it or can get it with reasonable efforts. 462 | 463 | You may not impose any further restrictions on the exercise of the 464 | rights granted or affirmed under this License. For example, you may 465 | not impose a license fee, royalty, or other charge for exercise of 466 | rights granted under this License, and you may not initiate litigation 467 | (including a cross-claim or counterclaim in a lawsuit) alleging that 468 | any patent claim is infringed by making, using, selling, offering for 469 | sale, or importing the Program or any portion of it. 470 | 471 | 11. Patents. 472 | 473 | A "contributor" is a copyright holder who authorizes use under this 474 | License of the Program or a work on which the Program is based. The 475 | work thus licensed is called the contributor's "contributor version". 476 | 477 | A contributor's "essential patent claims" are all patent claims 478 | owned or controlled by the contributor, whether already acquired or 479 | hereafter acquired, that would be infringed by some manner, permitted 480 | by this License, of making, using, or selling its contributor version, 481 | but do not include claims that would be infringed only as a 482 | consequence of further modification of the contributor version. For 483 | purposes of this definition, "control" includes the right to grant 484 | patent sublicenses in a manner consistent with the requirements of 485 | this License. 486 | 487 | Each contributor grants you a non-exclusive, worldwide, royalty-free 488 | patent license under the contributor's essential patent claims, to 489 | make, use, sell, offer for sale, import and otherwise run, modify and 490 | propagate the contents of its contributor version. 491 | 492 | In the following three paragraphs, a "patent license" is any express 493 | agreement or commitment, however denominated, not to enforce a patent 494 | (such as an express permission to practice a patent or covenant not to 495 | sue for patent infringement). To "grant" such a patent license to a 496 | party means to make such an agreement or commitment not to enforce a 497 | patent against the party. 498 | 499 | If you convey a covered work, knowingly relying on a patent license, 500 | and the Corresponding Source of the work is not available for anyone 501 | to copy, free of charge and under the terms of this License, through a 502 | publicly available network server or other readily accessible means, 503 | then you must either (1) cause the Corresponding Source to be so 504 | available, or (2) arrange to deprive yourself of the benefit of the 505 | patent license for this particular work, or (3) arrange, in a manner 506 | consistent with the requirements of this License, to extend the patent 507 | license to downstream recipients. "Knowingly relying" means you have 508 | actual knowledge that, but for the patent license, your conveying the 509 | covered work in a country, or your recipient's use of the covered work 510 | in a country, would infringe one or more identifiable patents in that 511 | country that you have reason to believe are valid. 512 | 513 | If, pursuant to or in connection with a single transaction or 514 | arrangement, you convey, or propagate by procuring conveyance of, a 515 | covered work, and grant a patent license to some of the parties 516 | receiving the covered work authorizing them to use, propagate, modify 517 | or convey a specific copy of the covered work, then the patent license 518 | you grant is automatically extended to all recipients of the covered 519 | work and works based on it. 520 | 521 | A patent license is "discriminatory" if it does not include within 522 | the scope of its coverage, prohibits the exercise of, or is 523 | conditioned on the non-exercise of one or more of the rights that are 524 | specifically granted under this License. You may not convey a covered 525 | work if you are a party to an arrangement with a third party that is 526 | in the business of distributing software, under which you make payment 527 | to the third party based on the extent of your activity of conveying 528 | the work, and under which the third party grants, to any of the 529 | parties who would receive the covered work from you, a discriminatory 530 | patent license (a) in connection with copies of the covered work 531 | conveyed by you (or copies made from those copies), or (b) primarily 532 | for and in connection with specific products or compilations that 533 | contain the covered work, unless you entered into that arrangement, 534 | or that patent license was granted, prior to 28 March 2007. 535 | 536 | Nothing in this License shall be construed as excluding or limiting 537 | any implied license or other defenses to infringement that may 538 | otherwise be available to you under applicable patent law. 539 | 540 | 12. No Surrender of Others' Freedom. 541 | 542 | If conditions are imposed on you (whether by court order, agreement or 543 | otherwise) that contradict the conditions of this License, they do not 544 | excuse you from the conditions of this License. If you cannot convey a 545 | covered work so as to satisfy simultaneously your obligations under this 546 | License and any other pertinent obligations, then as a consequence you may 547 | not convey it at all. For example, if you agree to terms that obligate you 548 | to collect a royalty for further conveying from those to whom you convey 549 | the Program, the only way you could satisfy both those terms and this 550 | License would be to refrain entirely from conveying the Program. 551 | 552 | 13. Use with the GNU Affero General Public License. 553 | 554 | Notwithstanding any other provision of this License, you have 555 | permission to link or combine any covered work with a work licensed 556 | under version 3 of the GNU Affero General Public License into a single 557 | combined work, and to convey the resulting work. The terms of this 558 | License will continue to apply to the part which is the covered work, 559 | but the special requirements of the GNU Affero General Public License, 560 | section 13, concerning interaction through a network will apply to the 561 | combination as such. 562 | 563 | 14. Revised Versions of this License. 564 | 565 | The Free Software Foundation may publish revised and/or new versions of 566 | the GNU General Public License from time to time. Such new versions will 567 | be similar in spirit to the present version, but may differ in detail to 568 | address new problems or concerns. 569 | 570 | Each version is given a distinguishing version number. If the 571 | Program specifies that a certain numbered version of the GNU General 572 | Public License "or any later version" applies to it, you have the 573 | option of following the terms and conditions either of that numbered 574 | version or of any later version published by the Free Software 575 | Foundation. If the Program does not specify a version number of the 576 | GNU General Public License, you may choose any version ever published 577 | by the Free Software Foundation. 578 | 579 | If the Program specifies that a proxy can decide which future 580 | versions of the GNU General Public License can be used, that proxy's 581 | public statement of acceptance of a version permanently authorizes you 582 | to choose that version for the Program. 583 | 584 | Later license versions may give you additional or different 585 | permissions. However, no additional obligations are imposed on any 586 | author or copyright holder as a result of your choosing to follow a 587 | later version. 588 | 589 | 15. Disclaimer of Warranty. 590 | 591 | THERE IS NO WARRANTY FOR THE PROGRAM, TO THE EXTENT PERMITTED BY 592 | APPLICABLE LAW. EXCEPT WHEN OTHERWISE STATED IN WRITING THE COPYRIGHT 593 | HOLDERS AND/OR OTHER PARTIES PROVIDE THE PROGRAM "AS IS" WITHOUT WARRANTY 594 | OF ANY KIND, EITHER EXPRESSED OR IMPLIED, INCLUDING, BUT NOT LIMITED TO, 595 | THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR 596 | PURPOSE. THE ENTIRE RISK AS TO THE QUALITY AND PERFORMANCE OF THE PROGRAM 597 | IS WITH YOU. SHOULD THE PROGRAM PROVE DEFECTIVE, YOU ASSUME THE COST OF 598 | ALL NECESSARY SERVICING, REPAIR OR CORRECTION. 599 | 600 | 16. Limitation of Liability. 601 | 602 | IN NO EVENT UNLESS REQUIRED BY APPLICABLE LAW OR AGREED TO IN WRITING 603 | WILL ANY COPYRIGHT HOLDER, OR ANY OTHER PARTY WHO MODIFIES AND/OR CONVEYS 604 | THE PROGRAM AS PERMITTED ABOVE, BE LIABLE TO YOU FOR DAMAGES, INCLUDING ANY 605 | GENERAL, SPECIAL, INCIDENTAL OR CONSEQUENTIAL DAMAGES ARISING OUT OF THE 606 | USE OR INABILITY TO USE THE PROGRAM (INCLUDING BUT NOT LIMITED TO LOSS OF 607 | DATA OR DATA BEING RENDERED INACCURATE OR LOSSES SUSTAINED BY YOU OR THIRD 608 | PARTIES OR A FAILURE OF THE PROGRAM TO OPERATE WITH ANY OTHER PROGRAMS), 609 | EVEN IF SUCH HOLDER OR OTHER PARTY HAS BEEN ADVISED OF THE POSSIBILITY OF 610 | SUCH DAMAGES. 611 | 612 | 17. Interpretation of Sections 15 and 16. 613 | 614 | If the disclaimer of warranty and limitation of liability provided 615 | above cannot be given local legal effect according to their terms, 616 | reviewing courts shall apply local law that most closely approximates 617 | an absolute waiver of all civil liability in connection with the 618 | Program, unless a warranty or assumption of liability accompanies a 619 | copy of the Program in return for a fee. 620 | 621 | END OF TERMS AND CONDITIONS 622 | 623 | How to Apply These Terms to Your New Programs 624 | 625 | If you develop a new program, and you want it to be of the greatest 626 | possible use to the public, the best way to achieve this is to make it 627 | free software which everyone can redistribute and change under these terms. 628 | 629 | To do so, attach the following notices to the program. It is safest 630 | to attach them to the start of each source file to most effectively 631 | state the exclusion of warranty; and each file should have at least 632 | the "copyright" line and a pointer to where the full notice is found. 633 | 634 | {one line to give the program's name and a brief idea of what it does.} 635 | Copyright (C) {year} {name of author} 636 | 637 | This program is free software: you can redistribute it and/or modify 638 | it under the terms of the GNU General Public License as published by 639 | the Free Software Foundation, either version 3 of the License, or 640 | (at your option) any later version. 641 | 642 | This program is distributed in the hope that it will be useful, 643 | but WITHOUT ANY WARRANTY; without even the implied warranty of 644 | MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 645 | GNU General Public License for more details. 646 | 647 | You should have received a copy of the GNU General Public License 648 | along with this program. If not, see . 649 | 650 | Also add information on how to contact you by electronic and paper mail. 651 | 652 | If the program does terminal interaction, make it output a short 653 | notice like this when it starts in an interactive mode: 654 | 655 | {project} Copyright (C) {year} {fullname} 656 | This program comes with ABSOLUTELY NO WARRANTY; for details type `show w'. 657 | This is free software, and you are welcome to redistribute it 658 | under certain conditions; type `show c' for details. 659 | 660 | The hypothetical commands `show w' and `show c' should show the appropriate 661 | parts of the General Public License. Of course, your program's commands 662 | might be different; for a GUI interface, you would use an "about box". 663 | 664 | You should also get your employer (if you work as a programmer) or school, 665 | if any, to sign a "copyright disclaimer" for the program, if necessary. 666 | For more information on this, and how to apply and follow the GNU GPL, see 667 | . 668 | 669 | The GNU General Public License does not permit incorporating your program 670 | into proprietary programs. If your program is a subroutine library, you 671 | may consider it more useful to permit linking proprietary applications with 672 | the library. If this is what you want to do, use the GNU Lesser General 673 | Public License instead of this License. But first, please read 674 | . 675 | 676 | -------------------------------------------------------------------------------- /MouseSensor.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | * MouseSensor.cpp - Reads data from MouseSensor 3 | * Author: Dimitris Platis (based on the Smartcar project by Team Pegasus) 4 | * License: GNU GPL v3 http://www.gnu.org/licenses/gpl-3.0.html 5 | */ 6 | #include "AndroidCar.h" 7 | 8 | MouseSensor::MouseSensor(){ 9 | } 10 | 11 | void MouseSensor::attach(HardwareSerial *mouseSerial){ 12 | _serial = mouseSerial; 13 | _serial->begin(115200); 14 | _serial->setTimeout(50); 15 | } 16 | 17 | boolean MouseSensor::available(){ 18 | return _serial->available(); 19 | } 20 | 21 | String MouseSensor::readLine(){ 22 | if (available()){ 23 | return readRawSerialLine(); 24 | }else{ 25 | return "error"; 26 | } 27 | } 28 | 29 | /* read whatever is in the buffer untill you reach the last available line and return it */ 30 | String MouseSensor::readLastLine(){ 31 | if (available()){ 32 | String input = ""; 33 | while (available()) input = readRawSerialLine(); 34 | return input; 35 | }else{ 36 | return "error"; 37 | } 38 | } 39 | 40 | int MouseSensor::getX(String mouseInput){ 41 | String x = mouseInput.substring(mouseInput.indexOf(':') + 1,mouseInput.indexOf(' ')); 42 | int out = x.toInt(); 43 | if (out || x.equals("0")){ 44 | return out; 45 | }else{ 46 | return -9999; 47 | } 48 | } 49 | 50 | int MouseSensor::getY(String mouseInput){ 51 | mouseInput.trim(); 52 | String y = mouseInput.substring(mouseInput.lastIndexOf(':') + 1); 53 | int out = y.toInt(); 54 | if (out || y.equals("0")){ 55 | return out; 56 | }else{ 57 | return -9999; 58 | } 59 | } 60 | 61 | 62 | String MouseSensor::readRawSerialLine(){ 63 | return _serial->readStringUntil('\n'); 64 | } 65 | 66 | void MouseSensor::clear(){ 67 | _serial->print("c"); 68 | } 69 | -------------------------------------------------------------------------------- /NewPing.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | * NewPing.cpp - Handles the timers. Based on the timers of NewPing library 3 | * Version: 0.3 4 | * Author: Dimitris Platis (based on the work by Tim Eckel - teckel@leethost.com) 5 | * License: GNU GPL v3 http://www.gnu.org/licenses/gpl-3.0.html 6 | */ 7 | #include "AndroidCar.h" 8 | 9 | // Variables used for timer functions 10 | void (*intFunc)(); 11 | void (*intFunc2)(); 12 | unsigned long _ms_cnt_reset; 13 | volatile unsigned long _ms_cnt; 14 | 15 | void NewPing::timer_start(unsigned long frequency, void (*userFunc)(void)) { 16 | timer_setup(); // Configure the timer interrupt. 17 | intFunc = NewPing::timer_start_cntdwn; // Timer events are sent here once every ms till user's frequency is reached. 18 | intFunc2 = userFunc; // User's function to call when user's frequency is reached. 19 | _ms_cnt = _ms_cnt_reset = frequency; // Current ms counter and reset value. 20 | 21 | #if defined (__AVR_ATmega32U4__) // Use Timer4 for ATmega32U4 (Teensy/Leonardo). 22 | OCR4C = 249; // Every count is 4uS, so 1ms = 250 counts - 1. 23 | TIMSK4 = (1<begin(9600); 14 | _serial->setTimeout(50); 15 | } 16 | 17 | boolean Razorboard::available(){ 18 | return _serial->available(); 19 | } 20 | 21 | String Razorboard::readLine(){ 22 | if (available()){ 23 | return readRawSerialLine(); 24 | }else{ 25 | return "error"; 26 | } 27 | } 28 | 29 | /* read whatever is in the buffer untill you reach the last available line and return it */ 30 | String Razorboard::readLastLine(){ 31 | if (available()){ 32 | String input = ""; 33 | input.reserve(32); 34 | while (available()) input = readRawSerialLine(); 35 | return input; 36 | }else{ 37 | return "error"; 38 | } 39 | } 40 | 41 | int Razorboard::getHeading(){ 42 | if (available()){ 43 | return getRawHeading(); 44 | }else { 45 | return -1000; 46 | } 47 | } 48 | 49 | int Razorboard::getLatestHeading(){ 50 | if (available()){ 51 | int heading = 0; 52 | while (available()) heading = getRawHeading(); 53 | return heading; 54 | }else{ 55 | return -1000; 56 | } 57 | } 58 | 59 | String Razorboard::readRawSerialLine(){ 60 | return _serial->readStringUntil('\n'); 61 | } 62 | 63 | int Razorboard::getRawHeading(){ 64 | String line = readRawSerialLine(); 65 | return line.substring(line.indexOf('=') + 1,line.indexOf(',')).toInt(); 66 | } 67 | -------------------------------------------------------------------------------- /SRF08.cpp: -------------------------------------------------------------------------------- 1 | #include "AndroidCar.h" 2 | 3 | const uint8_t SRF08::DEFAULT_PING_DELAY = 70; 4 | const uint8_t SRF08::DEFAULT_SRF08_ADDRESS = 112; 5 | 6 | static const uint8_t FIRST_ADDRESS = 112; //please refer to: http://www.robot-electronics.co.uk/htm/srf08tech.html 7 | static const uint8_t LAST_ADDRESS = 127; 8 | 9 | SRF08::SRF08(){} 10 | 11 | void SRF08::attach(const uint8_t address){ 12 | Wire.begin(); 13 | _address = address; 14 | _delay = DEFAULT_PING_DELAY; 15 | } 16 | 17 | void SRF08::setGain(const uint8_t gainValue){ 18 | Wire.beginTransmission(_address); //start i2c transmission 19 | Wire.write(0x01); //write to GAIN register (1) 20 | Wire.write(gainValue); //write the value 21 | Wire.endTransmission(); //end transmission 22 | } 23 | 24 | void SRF08::setRange(const uint8_t rangeValue){ 25 | Wire.beginTransmission(_address); //start i2c transmission 26 | Wire.write(0x02); //write to range register (1) 27 | Wire.write(rangeValue); //write the value // Max_Range = (rangeValue * 3.4) + 3.4 in centimeters 28 | Wire.endTransmission(); //end transmission 29 | } 30 | 31 | void SRF08::setPingDelay(const uint8_t milliseconds){ 32 | _delay = milliseconds; 33 | } 34 | 35 | int SRF08::getDistance(){ 36 | return ping(); 37 | } 38 | 39 | int SRF08::ping(){ 40 | Wire.beginTransmission(_address); 41 | Wire.write(byte(0x00)); 42 | Wire.write(byte(0x51)); 43 | Wire.endTransmission(); 44 | delay(_delay); 45 | Wire.beginTransmission(_address); 46 | Wire.write(byte(0x02)); 47 | Wire.endTransmission(); 48 | Wire.requestFrom(_address, uint8_t (2)); 49 | if (!Wire.available()) return -1; 50 | byte high = Wire.read(); 51 | byte low = Wire.read(); 52 | return (high << 8) + low; 53 | } 54 | 55 | void SRF08::changeAddress(uint8_t newAddress){ 56 | newAddress = constrain(newAddress, FIRST_ADDRESS, LAST_ADDRESS); //allow only valid values, between 112 and 127 57 | Wire.beginTransmission(_address); 58 | Wire.write(byte(0x00)); 59 | Wire.write(byte(0xA0)); 60 | Wire.endTransmission(); 61 | 62 | Wire.beginTransmission(_address); 63 | Wire.write(byte(0x00)); 64 | Wire.write(byte(0xAA)); 65 | Wire.endTransmission(); 66 | 67 | Wire.beginTransmission(_address); 68 | Wire.write(byte(0x00)); 69 | Wire.write(byte(0xA5)); 70 | Wire.endTransmission(); 71 | 72 | Wire.beginTransmission(_address); 73 | Wire.write(byte(0x00)); 74 | Wire.write(newAddress << 1); 75 | Wire.endTransmission(); 76 | 77 | _address = newAddress; 78 | } 79 | -------------------------------------------------------------------------------- /Sharp_IR.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | * Sharp_IR.cpp - Handles the infra red (Sharp GP2Y0A02 & GP2D120) sensors of the Smartcar 3 | * sensors. 4 | * Version: 0.3 5 | * Author: Dimitris Platis 6 | * Formula to convert volts to centimeters found in: http://luckylarry.co.uk/arduino-projects/arduino-using-a-sharp-ir-sensor-for-distance-calculation/ 7 | * Get original library at: http://code.google.com/p/arduino-new-measurement/ 8 | * License: GNU GPL v3 http://www.gnu.org/licenses/gpl-3.0.html 9 | */ 10 | 11 | #include "AndroidCar.h" 12 | 13 | /* ---- SHARP INFRARED SENSOR ---- */ 14 | //static const float SHARP_SENSITIVITY = 0.0048828125; //only use with GP2Y0A02 15 | //static const int MIN_IR_DISTANCE = 20; //Minimum reliable distance the sensor can measure. Derived from datasheet. For GP2Y0A02 16 | //static const int MAX_IR_DISTANCE = 80;//Maximum reliable distance the sensor can measure in real life conditions. Determined experimentally. GP2Y0A02 17 | static const int MIN_IR_DISTANCE = 4; //Minimum reliable distance the sensor can measure. Derived from datasheet. For GP2D120 18 | static const int MAX_IR_DISTANCE = 25;//Maximum reliable distance the sensor can measure in real life conditions.Determined experimentally. GP2D120 19 | const unsigned short Sharp_IR::IR_DEFAULT_ITERATIONS = 5; // The default value of iterations used in getMedianDistance() method. 20 | static const int IR_MEDIAN_DELAY = 15; //Millisecond delay between measurements in the getMedianDistance method. 21 | 22 | // Macro to convert from volts to centimeters. 23 | //#define VoltsToCentimeters(volts) (65*pow(volts, -1.10)) //decomment for Sharp GP2Y0A02 as well as in Sharp_IR::getDistance() 24 | #define VoltsToCentimeters(volts) ((2914 / (volts + 5)) - 1) //decomment for Sharp GP2D120 as well as in Sharp_IR::getDistance() 25 | 26 | 27 | Sharp_IR::Sharp_IR(){ 28 | } 29 | 30 | void Sharp_IR::attach(unsigned short IR_pin){ 31 | pinMode(IR_pin, INPUT); 32 | _IR_pin = IR_pin; 33 | } 34 | 35 | unsigned int Sharp_IR::getDistance(){ 36 | int volts = analogRead(_IR_pin); //* SHARP_SENSITIVITY; 37 | int distance = VoltsToCentimeters(volts); //decomment this line and comment the two previous ones for GP2D120 38 | if ((distance < MIN_IR_DISTANCE) || (distance > MAX_IR_DISTANCE)){ 39 | return 0; 40 | } 41 | return distance; 42 | } 43 | 44 | unsigned int Sharp_IR::getMedianDistance(short iterations){ 45 | unsigned int measurements[iterations], last; 46 | uint8_t j, i = 0; 47 | measurements[0] = 0; //initializing the array 48 | while (i < iterations) { 49 | last = Sharp_IR::getDistance(); //get IR measurements 50 | if (!last) { // measurement out of range. 51 | iterations--; // Skip, don't include as part of median. 52 | last = MAX_IR_DISTANCE; // Adjust "last" variable so delay is correct length. 53 | } else { // measurement in range, include as part of median. 54 | if (i > 0) { // Don't start sort till second measurement. 55 | for (j = i; j > 0 && measurements[j - 1] < last; j--) // Insertion sort loop. 56 | measurements[j] = measurements[j - 1]; // Shift measurement array to correct position for sort insertion. 57 | } else j = 0; // First measurement is starting point for sort. 58 | measurements[j] = last; // Add last measurement to array in sorted position. 59 | i++; // Move to next measurement. 60 | } 61 | if (i < iterations) delay(IR_MEDIAN_DELAY - (last >> 10)); // Millisecond delay between measurements. 62 | } 63 | return (measurements[iterations >> 1]); // Return the measurement distance median. 64 | } 65 | -------------------------------------------------------------------------------- /Sonar.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | * Sonar.cpp - Handles the ultra sound (HC-SR04 & SRF05) sensors of the Smartcar 3 | * Version: 0.2 4 | * Author: Dimitris Platis 5 | * Sonar class is essentially a stripped-down version of the NewPing library by Tim Eckel adjusted to Smartcar needs 6 | * Get original library at: http://code.google.com/p/arduino-new-ping/ 7 | * License: GNU GPL v3 http://www.gnu.org/licenses/gpl-3.0.html 8 | */ 9 | #include "AndroidCar.h" 10 | 11 | 12 | /* ------ SONAR ------ */ 13 | static const int MAX_US_DISTANCE = 70; // Maximum usable sensor distance is around 70cm. 14 | static const int US_ROUNDTRIP_CM = 57; // Microseconds (uS) it takes sound to travel round-trip 1cm (2cm total), uses integer to save compiled code space. 15 | static const int DISABLE_ONE_PIN = true; // Set to "true" to save up to 26 bytes of compiled code space if you're NOT using one pin sensor connections. 16 | 17 | // Probably shoudln't change these values unless you really know what you're doing. 18 | static const int NO_ECHO = 0; // Value returned if there's no ping echo within the specified MAX_SENSOR_DISTANCE 19 | static const int MAX_SENSOR_DELAY = 18000; // Maximum uS it takes for sensor to start the ping (SRF06 is the highest measured, just under 18ms). 20 | static const int ECHO_TIMER_FREQ = 24; // Frequency to check for a ping echo (every 24uS is about 0.4cm accuracy). 21 | static const int PING_MEDIAN_DELAY = 29; // Millisecond delay between pings in the getMedianDistance method. 22 | const unsigned short Sonar::SONAR_DEFAULT_ITERATIONS = 5; // The default value of iterations used in getMedianDistance() method. 23 | 24 | 25 | // Macro to convert from microseconds to centimeters. 26 | #define MicrosecondsToCentimeters(echoTime) (max((echoTime + US_ROUNDTRIP_CM / 2) / US_ROUNDTRIP_CM, (echoTime ? 1 : 0))) 27 | 28 | 29 | Sonar::Sonar() { 30 | } 31 | 32 | void Sonar::attach(unsigned short triggerPin, unsigned short echoPin){ 33 | _triggerBit = digitalPinToBitMask(triggerPin); // Get the port register bitmask for the trigger pin. 34 | _echoBit = digitalPinToBitMask(echoPin); // Get the port register bitmask for the echo pin. 35 | 36 | _triggerOutput = portOutputRegister(digitalPinToPort(triggerPin)); // Get the output port register for the trigger pin. 37 | _echoInput = portInputRegister(digitalPinToPort(echoPin)); // Get the input port register for the echo pin. 38 | 39 | _triggerMode = (uint8_t *) portModeRegister(digitalPinToPort(triggerPin)); // Get the port mode register for the trigger pin. 40 | 41 | _maxEchoTime = MAX_US_DISTANCE * US_ROUNDTRIP_CM + (US_ROUNDTRIP_CM / 2); // Calculate the maximum distance in uS. 42 | 43 | #if DISABLE_ONE_PIN == true 44 | *_triggerMode |= _triggerBit; // Set trigger pin to output. 45 | #endif 46 | } 47 | 48 | unsigned int Sonar::ping() { 49 | if (!ping_trigger()) return NO_ECHO; // Trigger a ping, if it returns false, return NO_ECHO to the calling function. 50 | while (*_echoInput & _echoBit) // Wait for the ping echo. 51 | if (micros() > _max_time) return NO_ECHO; // Stop the loop and return NO_ECHO (false) if we're beyond the set maximum distance. 52 | return (micros() - (_max_time - _maxEchoTime) - 5); // Calculate ping time, 5uS of overhead. 53 | } 54 | 55 | unsigned int Sonar::getDistance() { 56 | unsigned int echoTime = Sonar::ping(); // Calls the ping method and returns with the ping echo distance in uS. 57 | return MicrosecondsToCentimeters(echoTime); // Convert uS to centimeters. 58 | } 59 | 60 | unsigned int Sonar::getMedianDistance(short iterations) { 61 | unsigned int uS[iterations], last; 62 | uint8_t j, i = 0; 63 | uS[0] = NO_ECHO; 64 | while (i < iterations) { 65 | last = ping(); // Send ping. 66 | if (last == NO_ECHO) { // Ping out of range. 67 | iterations--; // Skip, don't include as part of median. 68 | last = _maxEchoTime; // Adjust "last" variable so delay is correct length. 69 | } else { // Ping in range, include as part of median. 70 | if (i > 0) { // Don't start sort till second ping. 71 | for (j = i; j > 0 && uS[j - 1] < last; j--) // Insertion sort loop. 72 | uS[j] = uS[j - 1]; // Shift ping array to correct position for sort insertion. 73 | } else j = 0; // First ping is starting point for sort. 74 | uS[j] = last; // Add last ping to array in sorted position. 75 | i++; // Move to next ping. 76 | } 77 | if (i < iterations) delay(PING_MEDIAN_DELAY - (last >> 10)); // Millisecond delay between pings. 78 | } 79 | return MicrosecondsToCentimeters((uS[iterations >> 1])); // Return the ping distance median. 80 | } 81 | 82 | 83 | /* Standard ping method helper functions */ 84 | boolean Sonar::ping_trigger() { 85 | #if DISABLE_ONE_PIN != true 86 | *_triggerMode |= _triggerBit; // Set trigger pin to output. 87 | #endif 88 | *_triggerOutput &= ~_triggerBit; // Set the trigger pin low, should already be low, but this will make sure it is. 89 | delayMicroseconds(4); // Wait for pin to go low, testing shows it needs 4uS to work every time. 90 | *_triggerOutput |= _triggerBit; // Set trigger pin high, this tells the sensor to send out a ping. 91 | delayMicroseconds(10); // Wait long enough for the sensor to realize the trigger pin is high. Sensor specs say to wait 10uS. 92 | *_triggerOutput &= ~_triggerBit; // Set trigger pin back to low. 93 | #if DISABLE_ONE_PIN != true 94 | *_triggerMode &= ~_triggerBit; // Set trigger pin to input (when using one Arduino pin this is technically setting the echo pin to input as both are tied to the same Arduino pin). 95 | #endif 96 | 97 | _max_time = micros() + MAX_SENSOR_DELAY; // Set a timeout for the ping to trigger. 98 | while (*_echoInput & _echoBit && micros() <= _max_time) {} // Wait for echo pin to clear. 99 | while (!(*_echoInput & _echoBit)) // Wait for ping to start. 100 | if (micros() > _max_time) return false; // Something went wrong, abort. 101 | 102 | _max_time = micros() + _maxEchoTime; // Ping started, set the timeout. 103 | return true; // Ping started successfully. 104 | } 105 | 106 | -------------------------------------------------------------------------------- /examples/androidCar/CarVariables.h: -------------------------------------------------------------------------------- 1 | #ifndef CarVariables_h 2 | #define CarVariables_h 3 | 4 | /* pin definitions */ 5 | #define SERVO_PIN 8 6 | #define ESC_PIN 9 7 | 8 | #define FRONT_US_TRIG_PIN 31 //orange 9 | #define FRONT_US_ECHO_PIN 33 //yellow 10 | 11 | #define FRONT_RIGHT_US_TRIG_PIN 29 //yellow 12 | #define FRONT_RIGHT_US_ECHO_PIN 27 //green 13 | 14 | #define REAR_US_TRIG_PIN 25 15 | #define REAR_US_ECHO_PIN 23 16 | 17 | #define SIDE_FRONT_IR_PIN A0 18 | #define SIDE_REAR_IR_PIN A1 19 | #define REAR_IR_PIN A2 20 | 21 | #define ENCODER_DIG_PIN 2 //INT0 22 | #define BT_STATE_PIN 4 23 | 24 | #define LEFT_IR_ARRAY A9 25 | #define RIGHT_IR_ARRAY A8 26 | #define WHITE 1 27 | #define BLACK 0 28 | 29 | #define OVERRIDE_SIGNAL_PIN 10 30 | #define MAX_WAVELENGTH 995 31 | #define MAX_STEERING_WAVELENGTH 2000 32 | #define OVERRIDE_THROTTLE_PIN 7 33 | #define OVERRIDE_SERVO_PIN 6 34 | #define NEUTRAL_FREQUENCY 1500 35 | #define OVERRIDE_FORWARD_SPEED 60 36 | #define OVERRIDE_BACKWARD_SPEED -250 37 | #define OVERRIDE_STEER_RIGHT 20 38 | #define OVERRIDE_STEER_LEFT -20 39 | #define OVERRIDE_FREQ_TOLERANCE 250 40 | 41 | /* macro definitions */ 42 | //read fast from bluetooth state pin (connected to digital pin 4 of Mega or Uno) 43 | #if defined(__AVR_ATmega2560__) 44 | #define bluetoothConnected (PING & B00100000) 45 | #elif defined(__AVR_ATmega328P__) 46 | #define bluetoothConnected (PIND & B00010000) 47 | #endif 48 | 49 | #endif 50 | -------------------------------------------------------------------------------- /examples/androidCar/README.md: -------------------------------------------------------------------------------- 1 | #Sketch set up 2 | 3 | This sketch utilizes the Autonomous Car library and the [Netstrings library](https://github.com/platisd/Netstrings) in order to send data fetched from the on board sensors to an Android phone, while receiving driving instructions from it. The current system schematic can be found in the [/res](res) folder, while various pin definitions are included in the [CarVariables.h](CarVariables.h) 4 | 5 | The Android application that interpets the data sent via this sketch and sends the driving instructions, can be found in the [Android-Car-duino](https://github.com/Petroula/Android-Car-duino/) repository. 6 | -------------------------------------------------------------------------------- /examples/androidCar/androidCar.ino: -------------------------------------------------------------------------------- 1 | /* The running arduino sketch on the Android Autonomous Vehicle by Team Pegasus 2 | * 3 | * Description: The vehicle is based on an Arduino Mega, that is connected to various sensors 4 | * (infrared, ultrasound, speed encoder, gyroscope and 9DOF IMU) and receives driving instructions 5 | * from an Android phone, via Bluetooth, that is attached on the top of the vehicle. The vehicle 6 | * can follow street lanes, park and overtake obstacles, using image processing on the Android phone. 7 | * 8 | * Author: Dimitris Platis 9 | */ 10 | #include 11 | #include 12 | #include 13 | #include 14 | #include "CarVariables.h" 15 | 16 | Car car(SERVO_PIN, ESC_PIN); //steering, esc 17 | Sonar frontSonar, frontRightSonar, rearSonar; 18 | Sharp_IR sideFrontIR, sideRearIR, rearIR; 19 | Odometer encoder; 20 | Gyroscope gyro; 21 | Razorboard razor; 22 | 23 | const unsigned short COM_FREQ = 100; 24 | unsigned long previousTransmission = 0; 25 | 26 | const unsigned short OVERRIDE_TIMEOUT = 3000; 27 | unsigned long overrideRelease = 0; 28 | boolean overrideTriggered = false; 29 | 30 | unsigned long prevCheck = 0; 31 | const unsigned short LEDrefreshRate = 200; 32 | 33 | const unsigned short GYRO_SAMPLING = 90; //to be optimized experimentally 34 | 35 | const unsigned short LINE = WHITE; //define the color of the street lines 36 | unsigned long prevInfraTime = 0; 37 | const unsigned short IR_INTERVAL = 500; 38 | 39 | void setup() { 40 | car.begin(); 41 | frontSonar.attach(FRONT_US_TRIG_PIN, FRONT_US_ECHO_PIN); 42 | frontRightSonar.attach(FRONT_RIGHT_US_TRIG_PIN, FRONT_RIGHT_US_ECHO_PIN); 43 | rearSonar.attach(REAR_US_TRIG_PIN, REAR_US_ECHO_PIN); 44 | sideFrontIR.attach(SIDE_FRONT_IR_PIN); 45 | sideRearIR.attach(SIDE_REAR_IR_PIN); 46 | rearIR.attach(REAR_IR_PIN); 47 | encoder.attach(ENCODER_DIG_PIN); 48 | encoder.begin(); //start counting 49 | gyro.attach(); 50 | gyro.begin(GYRO_SAMPLING); //start measuring 51 | razor.attach(&Serial3); 52 | pinMode(BT_STATE_PIN, INPUT); 53 | pinMode(LEFT_IR_ARRAY,INPUT); 54 | pinMode(RIGHT_IR_ARRAY,INPUT); 55 | setupChangeInterrupt(LEFT_IR_ARRAY); 56 | setupChangeInterrupt(RIGHT_IR_ARRAY); 57 | Serial2.begin(9600); 58 | Serial2.setTimeout(200); 59 | } 60 | 61 | void loop() { 62 | handleOverride(); //look for an override signal and if it exists disable bluetooth input 63 | handleInput(); //look for a serial input if override is not triggered and act accordingly 64 | updateLEDs(); //update LEDs depending on the mode we are currently in 65 | gyro.update(); //integrate gyroscope's readings 66 | transmitSensorData(); //fetch and transmit the sensor data in the correct intervals if bluetooth is connected 67 | } 68 | 69 | void updateLEDs() { 70 | if (millis() - prevCheck > LEDrefreshRate) { 71 | if (overrideTriggered) { //if override is triggered 72 | Serial3.print('m'); 73 | } else { //if override is NOT triggered 74 | if (!car.getSpeed()) { //if car is immobilized 75 | Serial3.print('s'); 76 | } else { //if car is running 77 | if (car.getAngle() > 0) { //if car turns right 78 | Serial3.print('r'); 79 | } else if (car.getAngle() < 0) { //if car turns left 80 | Serial3.print('l'); 81 | } else { //if car goes straight 82 | Serial3.print('i'); 83 | } 84 | } 85 | } 86 | prevCheck = millis(); 87 | } 88 | } 89 | 90 | void handleOverride() { 91 | if (int override = pulseIn(OVERRIDE_SIGNAL_PIN, HIGH, MAX_WAVELENGTH)) { 92 | overrideRelease = millis() + OVERRIDE_TIMEOUT; //time to re-enable Serial communication 93 | overrideTriggered = true; 94 | } 95 | } 96 | 97 | void transmitSensorData() { 98 | if (bluetoothConnected && (millis() - previousTransmission > COM_FREQ)) { 99 | String out; 100 | out = "US1-"; 101 | out += frontSonar.getDistance(); 102 | Serial2.println(encodedNetstring(out)); 103 | out = "US2-"; 104 | out += frontRightSonar.getDistance(); 105 | Serial2.println(encodedNetstring(out)); 106 | out = "US3-"; 107 | out += rearSonar.getDistance(); 108 | Serial2.println(encodedNetstring(out)); 109 | out = "IR1-"; 110 | out += sideFrontIR.getDistance(); 111 | Serial2.println(encodedNetstring(out)); 112 | out = "IR2-"; 113 | out += sideRearIR.getDistance(); 114 | Serial2.println(encodedNetstring(out)); 115 | out = "IR3-"; 116 | out += rearIR.getDistance(); 117 | Serial2.println(encodedNetstring(out)); 118 | out = "EN-"; 119 | out += encoder.getDistance(); 120 | Serial2.println(encodedNetstring(out)); 121 | out = "HE-"; 122 | out += abs(gyro.getAngularDisplacement()); 123 | Serial2.println(encodedNetstring(out)); 124 | out = "RZR-"; 125 | out += razor.getLatestHeading(); 126 | Serial2.println(encodedNetstring(out)); 127 | previousTransmission = millis(); 128 | } 129 | 130 | } 131 | 132 | void handleInput() { 133 | if (!overrideTriggered || (millis() > overrideRelease)) { 134 | if (overrideTriggered) { //this state is only entered when the OVERRIDE_TIMEOUT is over 135 | overrideTriggered = false; 136 | //after going out of the override mode, set speed and steering to initial position 137 | car.setSpeed(0); 138 | car.setAngle(0); 139 | } 140 | if (Serial2.available()) { 141 | String input = decodedNetstring(Serial2.readStringUntil(',')); 142 | if (input.startsWith("m")) { 143 | int throttle = input.substring(1).toInt(); 144 | car.setSpeed(throttle); 145 | } else if (input.startsWith("t")) { 146 | int degrees = input.substring(1).toInt(); 147 | car.setAngle(degrees); 148 | } else if (input.startsWith("h")) { 149 | gyro.begin(GYRO_SAMPLING); 150 | } else { 151 | Serial2.println(encodedNetstring("Bad input")); 152 | } 153 | } 154 | } else { //override mode 155 | unsigned short servoFreq = pulseIn(OVERRIDE_SERVO_PIN, HIGH, MAX_STEERING_WAVELENGTH); 156 | unsigned short throttleFreq = pulseIn(OVERRIDE_THROTTLE_PIN, HIGH, MAX_STEERING_WAVELENGTH); 157 | //handle override servo 158 | if (servoFreq) { //if you get 0, ignore it as it is between the pulses 159 | short diff = servoFreq - NEUTRAL_FREQUENCY; 160 | if (abs(diff) < OVERRIDE_FREQ_TOLERANCE) { 161 | car.setAngle(0); 162 | } else { 163 | if (servoFreq > NEUTRAL_FREQUENCY) { 164 | car.setAngle(OVERRIDE_STEER_RIGHT); 165 | } else { 166 | car.setAngle(OVERRIDE_STEER_LEFT); 167 | } 168 | } 169 | } 170 | //handle override throttle 171 | if (throttleFreq) { 172 | short diff = throttleFreq - NEUTRAL_FREQUENCY; 173 | if (abs(diff) < OVERRIDE_FREQ_TOLERANCE) { 174 | car.setSpeed(0); 175 | } else { 176 | if (throttleFreq > NEUTRAL_FREQUENCY) { 177 | car.setSpeed(OVERRIDE_FORWARD_SPEED); 178 | } else { 179 | car.setSpeed(OVERRIDE_BACKWARD_SPEED); 180 | } 181 | } 182 | } 183 | while (Serial2.read() != -1); //discard incoming data while on override 184 | } 185 | } 186 | 187 | void setupChangeInterrupt(unsigned short pin) { 188 | *digitalPinToPCMSK(pin) |= bit (digitalPinToPCMSKbit(pin)); // enable pin 189 | PCIFR |= bit (digitalPinToPCICRbit(pin)); // clear any outstanding interrupt 190 | PCICR |= bit (digitalPinToPCICRbit(pin)); // enable interrupt for the group 191 | } 192 | 193 | //the interrupt service routine for pins A8 until A15 on Arduino mega 194 | ISR (PCINT2_vect) { 195 | //if either of the IR arrays have detected a line 196 | unsigned short leftArray = digitalRead(LEFT_IR_ARRAY); 197 | unsigned short rightArray = digitalRead(RIGHT_IR_ARRAY); 198 | if ((leftArray == LINE) || (rightArray == LINE)){ 199 | unsigned long currentTime = millis(); 200 | //if we have NOT detected the line "lately" 201 | if (currentTime - prevInfraTime > IR_INTERVAL){ 202 | if (leftArray == LINE) Serial2.println(encodedNetstring("lineL")); //send that we have detected the left line 203 | if (rightArray == LINE) Serial2.println(encodedNetstring("lineR")); //send that we have detected the right line 204 | prevInfraTime = currentTime; //save the time that we transmitted the line detection 205 | } 206 | } 207 | } 208 | -------------------------------------------------------------------------------- /examples/androidCar/res/android_vehicle_bb.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/platisd/AndroidCar/432ae929092edd4bef92710085009936a9e346c2/examples/androidCar/res/android_vehicle_bb.png -------------------------------------------------------------------------------- /examples/androidCar/res/system_schematic.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/platisd/AndroidCar/432ae929092edd4bef92710085009936a9e346c2/examples/androidCar/res/system_schematic.png -------------------------------------------------------------------------------- /keywords.txt: -------------------------------------------------------------------------------- 1 | Sonar KEYWORD1 2 | Sharp_IR KEYWORD1 3 | Odometer KEYWORD1 4 | Gyroscope KEYWORD1 5 | Car KEYWORD1 6 | NewPing KEYWORD1 7 | Razorboard KEYWORD1 8 | MouseSensor KEYWORD1 9 | attach KEYWORD2 10 | getDistance KEYWORD2 11 | getMedianDistance KEYWORD2 12 | getAngularDisplacement KEYWORD2 13 | timer_start KEYWORD2 14 | timer_stop KEYWORD2 15 | setSpeed KEYWORD2 16 | setAngle KEYWORD2 17 | setSteeringWheel KEYWORD2 18 | getSpeed KEYWORD2 19 | getAngle KEYWORD2 20 | readLine KEYWORD2 21 | readLastLine KEYWORD2 22 | getHeading KEYWORD2 23 | getLatestHeading KEYWORD2 24 | getX KEYWORD2 25 | getY KEYWORD2 26 | clear KEYWORD2 27 | --------------------------------------------------------------------------------