├── .gitignore ├── uml ├── arduinofuzzy.vpp └── class-diagram.png ├── library.properties ├── FuzzyInput.h ├── FuzzySet.h ├── FuzzyRule.h ├── LICENSE ├── CHANGELOG.md ├── Makefile ├── FuzzyRuleConsequent.h ├── FuzzyOutput.h ├── FuzzyIO.h ├── FuzzyInput.cpp ├── FuzzyComposition.h ├── FuzzyRule.cpp ├── FuzzyRuleAntecedent.h ├── Fuzzy.h ├── FuzzyRuleConsequent.cpp ├── FuzzyIO.cpp ├── FuzzySet.cpp ├── examples ├── arduino_simple_sample │ └── arduino_simple_sample.ino ├── general_simple_sample │ └── general_simple_sample.cpp ├── general_advanced_sample │ └── general_advanced_sample.cpp └── arduino_advanced_sample │ └── arduino_advanced_sample.ino ├── README.md ├── tests ├── GeneralTest.cpp └── FuzzyTest.cpp ├── Fuzzy.cpp ├── FuzzyRuleAntecedent.cpp ├── FuzzyComposition.cpp └── FuzzyOutput.cpp /.gitignore: -------------------------------------------------------------------------------- 1 | *.o 2 | *.bin 3 | *.bin.dSYM 4 | uml/* 5 | .DS_Store 6 | .vscode 7 | *.txt 8 | -------------------------------------------------------------------------------- /uml/arduinofuzzy.vpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/alvesoaj/eFLL/HEAD/uml/arduinofuzzy.vpp -------------------------------------------------------------------------------- /uml/class-diagram.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/alvesoaj/eFLL/HEAD/uml/class-diagram.png -------------------------------------------------------------------------------- /library.properties: -------------------------------------------------------------------------------- 1 | name=eFLL 2 | version=1.4.1 3 | author=AJ Alves , Dr. Ricardo Lira , Msc. Marvin Lemos , Douglas S. Kridi , Kannya Leal 4 | maintainer=AJ Alves 5 | sentence=eFLL (Embedded Fuzzy Logic Library). 6 | paragraph=eFLL is a standard library for Embedded Systems to implement easy and eficient Fuzzy Systems. 7 | category=Other 8 | url=https://github.com/zerokol/eFLL 9 | architectures=* 10 | includes=Fuzzy.h -------------------------------------------------------------------------------- /FuzzyInput.h: -------------------------------------------------------------------------------- 1 | /* 2 | * Robotic Research Group (RRG) 3 | * State University of Piauí (UESPI), Brazil - Piauí - Teresina 4 | * 5 | * FuzzyInput.h 6 | * 7 | * Author: AJ Alves 8 | * Co authors: Dr. Ricardo Lira 9 | * Msc. Marvin Lemos 10 | * Douglas S. Kridi 11 | * Kannya Leal 12 | */ 13 | #ifndef FUZZYINPUT_H 14 | #define FUZZYINPUT_H 15 | 16 | // IMPORTING NECESSARY LIBRARIES 17 | #include "FuzzyIO.h" 18 | 19 | class FuzzyInput : public FuzzyIO 20 | { 21 | public: 22 | // CONTRUCTORS 23 | FuzzyInput(); 24 | FuzzyInput(int index); 25 | // DESTRUCTOR 26 | ~FuzzyInput(); 27 | // PUBLIC METHODS 28 | bool calculateFuzzySetPertinences(); 29 | }; 30 | #endif -------------------------------------------------------------------------------- /FuzzySet.h: -------------------------------------------------------------------------------- 1 | /* 2 | * Robotic Research Group (RRG) 3 | * State University of Piauí (UESPI), Brazil - Piauí - Teresina 4 | * 5 | * FuzzySet.h 6 | * 7 | * Author: AJ Alves 8 | * Co authors: Dr. Ricardo Lira 9 | * Msc. Marvin Lemos 10 | * Douglas S. Kridi 11 | * Kannya Leal 12 | */ 13 | #ifndef FUZZYSET_H 14 | #define FUZZYSET_H 15 | 16 | class FuzzySet 17 | { 18 | public: 19 | // CONTRUCTORS 20 | FuzzySet(); 21 | FuzzySet(float a, float b, float c, float d); 22 | // PUBLIC METHODS 23 | float getPointA(); 24 | float getPointB(); 25 | float getPointC(); 26 | float getPointD(); 27 | bool calculatePertinence(float crispValue); 28 | void setPertinence(float pertinence); 29 | float getPertinence(); 30 | void reset(); 31 | 32 | private: 33 | // PRIVATE VARIABLES 34 | float a; 35 | float b; 36 | float c; 37 | float d; 38 | float pertinence; 39 | }; 40 | #endif -------------------------------------------------------------------------------- /FuzzyRule.h: -------------------------------------------------------------------------------- 1 | /* 2 | * Robotic Research Group (RRG) 3 | * State University of Piauí (UESPI), Brazil - Piauí - Teresina 4 | * 5 | * FuzzyRule.h 6 | * 7 | * Author: AJ Alves 8 | * Co authors: Dr. Ricardo Lira 9 | * Msc. Marvin Lemos 10 | * Douglas S. Kridi 11 | * Kannya Leal 12 | */ 13 | #ifndef FUZZYRULE_H 14 | #define FUZZYRULE_H 15 | 16 | // IMPORTING NECESSARY LIBRARIES 17 | #include "FuzzyRuleAntecedent.h" 18 | #include "FuzzyRuleConsequent.h" 19 | 20 | class FuzzyRule 21 | { 22 | public: 23 | // CONTRUCTORS 24 | FuzzyRule(); 25 | FuzzyRule(int index, FuzzyRuleAntecedent *fuzzyRuleAntecedent, FuzzyRuleConsequent *fuzzyRuleConsequent); 26 | // PUBLIC METHODS 27 | int getIndex(); 28 | bool evaluateExpression(); 29 | bool isFired(); 30 | 31 | private: 32 | // PRIVATE VARIABLES 33 | int index; 34 | bool fired; 35 | FuzzyRuleAntecedent *fuzzyRuleAntecedent; 36 | FuzzyRuleConsequent *fuzzyRuleConsequent; 37 | }; 38 | #endif -------------------------------------------------------------------------------- /LICENSE: -------------------------------------------------------------------------------- 1 | MIT License 2 | 3 | Copyright (c) 2017 AJ Alves 4 | 5 | Permission is hereby granted, free of charge, to any person obtaining a copy 6 | of this software and associated documentation files (the "Software"), to deal 7 | in the Software without restriction, including without limitation the rights 8 | to use, copy, modify, merge, publish, distribute, sublicense, and/or sell 9 | copies of the Software, and to permit persons to whom the Software is 10 | furnished to do so, subject to the following conditions: 11 | 12 | The above copyright notice and this permission notice shall be included in all 13 | copies or substantial portions of the Software. 14 | 15 | THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR 16 | IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, 17 | FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE 18 | AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER 19 | LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, 20 | OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE 21 | SOFTWARE. 22 | -------------------------------------------------------------------------------- /CHANGELOG.md: -------------------------------------------------------------------------------- 1 | # Changelog 2 | 3 | All notable changes to this project will be documented in this file. 4 | 5 | The format is based on [Keep a Changelog](http://keepachangelog.com/en/1.0.0/) 6 | and this project adheres to [Semantic Versioning](http://semver.org/spec/v2.0.0.html). 7 | 8 | ## [1.4.1] - 2021-07-06 9 | 10 | - Improve fuzzy set calculations 11 | 12 | ## [Unreleased] 13 | 14 | ## [1.1.0] - 2019-02-22 15 | 16 | ### Added 17 | 18 | - library.properties file to submit for Arduino Library Defaults. 19 | 20 | ### Changed 21 | 22 | - A complete code review, code formatting, translating and commenting . 23 | - A Bug at FuzzyOutput was found, in the way of calculate builds the points of FuzzyComposition. 24 | - Some methods was renamed and others created (for helps in tests). 25 | - A complete check in tests to ensure library accuracy. 26 | 27 | ### Removed 28 | 29 | - None. 30 | 31 | ## [1.0.10] - 2017-08-21 32 | 33 | ### Added 34 | 35 | - CHANGELOG.md file to document this project. 36 | 37 | ### Changed 38 | 39 | - The way that FuzzyOutput truncate trapezoidal functions, improve the accuracy. 40 | - File headers with author references. 41 | 42 | ### Removed 43 | 44 | - None. 45 | -------------------------------------------------------------------------------- /Makefile: -------------------------------------------------------------------------------- 1 | all: 2 | $(MAKE) lib 3 | $(MAKE) test 4 | 5 | lib: 6 | gcc -c ./*.cpp 7 | gcc -c *.cpp 8 | g++ ./examples/general_simple_sample/general_simple_sample.cpp Fuzzy.o FuzzyComposition.o FuzzyIO.o FuzzyInput.o FuzzyOutput.o FuzzyRule.o FuzzyRuleAntecedent.o FuzzyRuleConsequent.o FuzzySet.o -o examples/general_simple_sample/general_simple_sample.bin -fPIC -O2 -g -Wall 9 | g++ ./examples/general_advanced_sample/general_advanced_sample.cpp Fuzzy.o FuzzyComposition.o FuzzyIO.o FuzzyInput.o FuzzyOutput.o FuzzyRule.o FuzzyRuleAntecedent.o FuzzyRuleConsequent.o FuzzySet.o -o examples/general_advanced_sample/general_advanced_sample.bin -fPIC -O2 -g -Wall 10 | 11 | test: 12 | g++ ./tests/GeneralTest.cpp Fuzzy.o FuzzyComposition.o FuzzyIO.o FuzzyInput.o FuzzyOutput.o FuzzyRule.o FuzzyRuleAntecedent.o FuzzyRuleConsequent.o FuzzySet.o -o tests/GeneralTest.bin -fPIC -O2 -g -Wall 13 | g++ ./tests/FuzzyTest.cpp Fuzzy.o FuzzyComposition.o FuzzyIO.o FuzzyInput.o FuzzyOutput.o FuzzyRule.o FuzzyRuleAntecedent.o FuzzyRuleConsequent.o FuzzySet.o /usr/local/lib/libgtest.a -o tests/FuzzyTest.bin -fPIC -O2 -g -Wall -lpthread 14 | 15 | clean: 16 | rm -f *.o 17 | rm -f ./examples/*/*.bin 18 | rm -f ./tests/*.bin 19 | rm -rf ./tests/*.bin.* -------------------------------------------------------------------------------- /FuzzyRuleConsequent.h: -------------------------------------------------------------------------------- 1 | /* 2 | * Robotic Research Group (RRG) 3 | * State University of Piauí (UESPI), Brazil - Piauí - Teresina 4 | * 5 | * FuzzyRuleConsequent.h 6 | * 7 | * Author: AJ Alves 8 | * Co authors: Dr. Ricardo Lira 9 | * Msc. Marvin Lemos 10 | * Douglas S. Kridi 11 | * Kannya Leal 12 | */ 13 | #ifndef FUZZYRULECONSEQUENT_H 14 | #define FUZZYRULECONSEQUENT_H 15 | 16 | // IMPORTING NECESSARY LIBRARIES 17 | #include 18 | #include "FuzzySet.h" 19 | 20 | // Array struct for fuzzySet (for Output) objects 21 | struct fuzzySetOutputArray 22 | { 23 | FuzzySet *fuzzySet; 24 | fuzzySetOutputArray *next; 25 | }; 26 | 27 | class FuzzyRuleConsequent 28 | { 29 | public: 30 | // CONTRUCTORS 31 | FuzzyRuleConsequent(); 32 | // DESTRUCTOR 33 | ~FuzzyRuleConsequent(); 34 | // PUBLIC METHODS 35 | bool addOutput(FuzzySet *fuzzySet); 36 | bool evaluate(float power); 37 | 38 | private: 39 | // PRIVATE VARIABLES 40 | fuzzySetOutputArray *fuzzySetOutputs; 41 | 42 | // PRIVATE METHODS 43 | void cleanFuzzySets(fuzzySetOutputArray *aux); 44 | }; 45 | #endif -------------------------------------------------------------------------------- /FuzzyOutput.h: -------------------------------------------------------------------------------- 1 | /* 2 | * Robotic Research Group (RRG) 3 | * State University of Piauí (UESPI), Brazil - Piauí - Teresina 4 | * 5 | * FuzzyOutput.h 6 | * 7 | * Author: AJ Alves 8 | * Co authors: Dr. Ricardo Lira 9 | * Msc. Marvin Lemos 10 | * Douglas S. Kridi 11 | * Kannya Leal 12 | */ 13 | #ifndef FUZZYOUTPUT_H 14 | #define FUZZYOUTPUT_H 15 | 16 | // IMPORTING NECESSARY LIBRARIES 17 | #include "FuzzyIO.h" 18 | #include "FuzzyComposition.h" 19 | 20 | class FuzzyOutput : public FuzzyIO 21 | { 22 | public: 23 | // CONTRUCTORS 24 | FuzzyOutput(); 25 | FuzzyOutput(int index); 26 | // DESTRUCTOR 27 | ~FuzzyOutput(); 28 | // PUBLIC METHODS 29 | bool truncate(); 30 | float getCrispOutput(); 31 | bool order(); 32 | FuzzyComposition *getFuzzyComposition(); 33 | 34 | private: 35 | // PRIVATE VARIABLES 36 | FuzzyComposition *fuzzyComposition; 37 | 38 | // PRIVATE METHODS 39 | bool swap(fuzzySetArray *fuzzySetA, fuzzySetArray *fuzzySetB); 40 | bool rebuild(float x1, float y1, float x2, float y2, float x3, float y3, float x4, float y4, float *point, float *pertinence); 41 | }; 42 | #endif -------------------------------------------------------------------------------- /FuzzyIO.h: -------------------------------------------------------------------------------- 1 | /* 2 | * Robotic Research Group (RRG) 3 | * State University of Piauí (UESPI), Brazil - Piauí - Teresina 4 | * 5 | * FuzzyIO.h 6 | * 7 | * Author: AJ Alves 8 | * Co authors: Dr. Ricardo Lira 9 | * Msc. Marvin Lemos 10 | * Douglas S. Kridi 11 | * Kannya Leal 12 | */ 13 | #ifndef FUZZYIO_H 14 | #define FUZZYIO_H 15 | 16 | // IMPORTING NECESSARY LIBRARIES 17 | #include 18 | #include "FuzzySet.h" 19 | 20 | // Array struct for FuzzySet objects 21 | struct fuzzySetArray 22 | { 23 | FuzzySet *fuzzySet; 24 | fuzzySetArray *next; 25 | }; 26 | 27 | class FuzzyIO 28 | { 29 | public: 30 | // CONTRUCTORS 31 | FuzzyIO(); 32 | FuzzyIO(int index); 33 | // DESTRUCTOR 34 | ~FuzzyIO(); 35 | // PUBLIC METHODS 36 | int getIndex(); 37 | void setCrispInput(float crispInput); 38 | float getCrispInput(); 39 | bool addFuzzySet(FuzzySet *fuzzySet); 40 | void resetFuzzySets(); 41 | 42 | protected: 43 | // PROTECTED VARIABLES 44 | int index; 45 | float crispInput; 46 | fuzzySetArray *fuzzySets; 47 | 48 | // PROTECTED METHODS 49 | void cleanFuzzySets(fuzzySetArray *aux); 50 | }; 51 | #endif -------------------------------------------------------------------------------- /FuzzyInput.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | * Robotic Research Group (RRG) 3 | * State University of Piauí (UESPI), Brazil - Piauí - Teresina 4 | * 5 | * FuzzyInput.cpp 6 | * 7 | * Author: AJ Alves 8 | * Co authors: Dr. Ricardo Lira 9 | * Msc. Marvin Lemos 10 | * Douglas S. Kridi 11 | * Kannya Leal 12 | */ 13 | #include "FuzzyInput.h" 14 | 15 | // CONTRUCTORS 16 | FuzzyInput::FuzzyInput() : FuzzyIO() 17 | { 18 | // no custom construction, using the father (FuzzyIO) constructor 19 | } 20 | 21 | FuzzyInput::FuzzyInput(int index) : FuzzyIO(index) 22 | { 23 | // no custom construction, using the father (FuzzyIO) constructor 24 | } 25 | 26 | // DESTRUCTOR 27 | FuzzyInput::~FuzzyInput() 28 | { 29 | // no custom destruction, using the father (FuzzyIO) destructor 30 | } 31 | 32 | // PUBLIC METHODS 33 | 34 | // Method to calculate the pertinence of all FuzzySet 35 | bool FuzzyInput::calculateFuzzySetPertinences() 36 | { 37 | // auxiliary variable to handle the operation 38 | fuzzySetArray *aux = this->fuzzySets; 39 | // while not in the end of the array, iterate 40 | while (aux != NULL) 41 | { 42 | // call calculatePertinence for each FuzzySet 43 | aux->fuzzySet->calculatePertinence(this->crispInput); 44 | aux = aux->next; 45 | } 46 | return true; 47 | } -------------------------------------------------------------------------------- /FuzzyComposition.h: -------------------------------------------------------------------------------- 1 | /* 2 | * Robotic Research Group (RRG) 3 | * State University of Piauí (UESPI), Brazil - Piauí - Teresina 4 | * 5 | * FuzzyComposition.h 6 | * 7 | * Author: AJ Alves 8 | * Co authors: Dr. Ricardo Lira 9 | * Msc. Marvin Lemos 10 | * Douglas S. Kridi 11 | * Kannya Leal 12 | */ 13 | #ifndef FUZZYCOMPOSITION_H 14 | #define FUZZYCOMPOSITION_H 15 | 16 | // IMPORTING NECESSARY LIBRARIES 17 | #include 18 | 19 | // CONSTANTS 20 | #define EPSILON_VALUE 1.0E-3 21 | 22 | // Array struct for points objects 23 | struct pointsArray 24 | { 25 | pointsArray *previous; 26 | float point; 27 | float pertinence; 28 | pointsArray *next; 29 | }; 30 | 31 | class FuzzyComposition 32 | { 33 | public: 34 | // CONTRUCTORS 35 | FuzzyComposition(); 36 | // DESTRUCTOR 37 | ~FuzzyComposition(); 38 | // PUBLIC METHODS 39 | bool addPoint(float point, float pertinence); 40 | bool checkPoint(float point, float pertinence); 41 | bool build(); 42 | float calculate(); 43 | bool empty(); 44 | int countPoints(); 45 | 46 | private: 47 | // PRIVATE VARIABLES 48 | pointsArray *points; 49 | 50 | // PRIVATE METHODS 51 | void cleanPoints(pointsArray *aux); 52 | bool rebuild(pointsArray *aSegmentBegin, pointsArray *aSegmentEnd, pointsArray *bSegmentBegin, pointsArray *bSegmentEnd); 53 | bool rmvPoint(pointsArray *point); 54 | }; 55 | #endif -------------------------------------------------------------------------------- /FuzzyRule.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | * Robotic Research Group (RRG) 3 | * State University of Piauí (UESPI), Brazil - Piauí - Teresina 4 | * 5 | * FuzzyOutput.cpp 6 | * 7 | * Author: AJ Alves 8 | * Co authors: Dr. Ricardo Lira 9 | * Msc. Marvin Lemos 10 | * Douglas S. Kridi 11 | * Kannya Leal 12 | */ 13 | #include "FuzzyRule.h" 14 | 15 | // CONTRUCTORS 16 | FuzzyRule::FuzzyRule() 17 | { 18 | } 19 | 20 | FuzzyRule::FuzzyRule(int index, FuzzyRuleAntecedent *fuzzyRuleAntecedent, FuzzyRuleConsequent *fuzzyRuleConsequent) 21 | { 22 | this->index = index; 23 | this->fired = false; 24 | this->fuzzyRuleAntecedent = fuzzyRuleAntecedent; 25 | this->fuzzyRuleConsequent = fuzzyRuleConsequent; 26 | } 27 | 28 | // PUBLIC METHODS 29 | 30 | // Method to get the value of index 31 | int FuzzyRule::getIndex() 32 | { 33 | return this->index; 34 | } 35 | 36 | // Method to evaluate the total expression 37 | bool FuzzyRule::evaluateExpression() 38 | { 39 | // check if the FuzzyRuleAntecedent and FuzzyRuleConsequent are valid 40 | if (this->fuzzyRuleAntecedent != NULL && this->fuzzyRuleConsequent != NULL) 41 | { 42 | // call the evaluator in the FuzzyRuleAntecedent 43 | float powerOfAntecedent = this->fuzzyRuleAntecedent->evaluate(); 44 | // if the power of FuzzyRuleAntecedent is bigget the 0.0, this rule was fired, else, no 45 | (powerOfAntecedent > 0.0) ? (this->fired = true) : (this->fired = false); 46 | // pass the power of FuzzyRuleAntecedent to FuzzyRuleConsequent by its evaluator 47 | this->fuzzyRuleConsequent->evaluate(powerOfAntecedent); 48 | } 49 | return this->fired; 50 | } 51 | 52 | // Method to get the value of fired 53 | bool FuzzyRule::isFired() 54 | { 55 | return this->fired; 56 | } -------------------------------------------------------------------------------- /FuzzyRuleAntecedent.h: -------------------------------------------------------------------------------- 1 | /* 2 | * Robotic Research Group (RRG) 3 | * State University of Piauí (UESPI), Brazil - Piauí - Teresina 4 | * 5 | * FuzzyRuleAntecedent.h 6 | * 7 | * Author: AJ Alves 8 | * Co authors: Dr. Ricardo Lira 9 | * Msc. Marvin Lemos 10 | * Douglas S. Kridi 11 | * Kannya Leal 12 | */ 13 | #ifndef FUZZYRULEANTECEDENT_H 14 | #define FUZZYRULEANTECEDENT_H 15 | 16 | // IMPORTING NECESSARY LIBRARIES 17 | #include 18 | #include "FuzzySet.h" 19 | 20 | // CONSTANTS 21 | // possible logic operators 22 | #define OP_AND 1 23 | #define OP_OR 2 24 | // possible join associations modes 25 | #define MODE_FS 1 26 | #define MODE_FS_FS 2 27 | #define MODE_FS_FRA 3 28 | #define MODE_FRA_FRA 4 29 | 30 | class FuzzyRuleAntecedent 31 | { 32 | public: 33 | // CONTRUCTORS 34 | FuzzyRuleAntecedent(); 35 | // PUBLIC METHODS 36 | bool joinSingle(FuzzySet *fuzzySet); 37 | bool joinWithAND(FuzzySet *fuzzySet1, FuzzySet *fuzzySet2); 38 | bool joinWithOR(FuzzySet *fuzzySet1, FuzzySet *fuzzySet2); 39 | bool joinWithAND(FuzzySet *fuzzySet, FuzzyRuleAntecedent *fuzzyRuleAntecedent); 40 | bool joinWithAND(FuzzyRuleAntecedent *fuzzyRuleAntecedent, FuzzySet *fuzzySet); 41 | bool joinWithOR(FuzzySet *fuzzySet, FuzzyRuleAntecedent *fuzzyRuleAntecedent); 42 | bool joinWithOR(FuzzyRuleAntecedent *fuzzyRuleAntecedent, FuzzySet *fuzzySet); 43 | bool joinWithAND(FuzzyRuleAntecedent *fuzzyRuleAntecedent1, FuzzyRuleAntecedent *fuzzyRuleAntecedent2); 44 | bool joinWithOR(FuzzyRuleAntecedent *fuzzyRuleAntecedent1, FuzzyRuleAntecedent *fuzzyRuleAntecedent2); 45 | float evaluate(); 46 | 47 | private: 48 | // PRIVATE VARIABLES 49 | int op; 50 | int mode; 51 | FuzzySet *fuzzySet1; 52 | FuzzySet *fuzzySet2; 53 | FuzzyRuleAntecedent *fuzzyRuleAntecedent1; 54 | FuzzyRuleAntecedent *fuzzyRuleAntecedent2; 55 | }; 56 | #endif -------------------------------------------------------------------------------- /Fuzzy.h: -------------------------------------------------------------------------------- 1 | /* 2 | * Robotic Research Group (RRG) 3 | * State University of Piauí (UESPI), Brazil - Piauí - Teresina 4 | * 5 | * Fuzzy.h 6 | * 7 | * Author: AJ Alves 8 | * Co authors: Dr. Ricardo Lira 9 | * Msc. Marvin Lemos 10 | * Douglas S. Kridi 11 | * Kannya Leal 12 | */ 13 | #ifndef FUZZY_H 14 | #define FUZZY_H 15 | 16 | // IMPORTING NECESSARY LIBRARIES 17 | #include 18 | #include "FuzzyInput.h" 19 | #include "FuzzyOutput.h" 20 | #include "FuzzyRule.h" 21 | 22 | // Array struct for FuzzyInput objects 23 | struct fuzzyInputArray 24 | { 25 | FuzzyInput *fuzzyInput; 26 | fuzzyInputArray *next; 27 | }; 28 | 29 | // Array struct for FuzzyOutput objects 30 | struct fuzzyOutputArray 31 | { 32 | FuzzyOutput *fuzzyOutput; 33 | fuzzyOutputArray *next; 34 | }; 35 | 36 | // Array struct for FuzzyRule objects 37 | struct fuzzyRuleArray 38 | { 39 | FuzzyRule *fuzzyRule; 40 | fuzzyRuleArray *next; 41 | }; 42 | 43 | // Main class of this library 44 | class Fuzzy 45 | { 46 | public: 47 | // CONTRUCTORS 48 | Fuzzy(); 49 | 50 | // DESTRUCTOR 51 | ~Fuzzy(); 52 | 53 | // PUBLIC METHODS 54 | bool addFuzzyInput(FuzzyInput *fuzzyInput); 55 | bool addFuzzyOutput(FuzzyOutput *fuzzyOutput); 56 | bool addFuzzyRule(FuzzyRule *fuzzyRule); 57 | bool setInput(int fuzzyInputIndex, float crispValue); 58 | bool fuzzify(); 59 | bool isFiredRule(int fuzzyRuleIndex); 60 | float defuzzify(int fuzzyOutputIndex); 61 | 62 | private: 63 | // PRIVATE VARIABLES 64 | // pointers to manage the array of FuzzyInput 65 | fuzzyInputArray *fuzzyInputs; 66 | // pointers to manage the array of FuzzyOutput 67 | fuzzyOutputArray *fuzzyOutputs; 68 | // pointers to manage the array of FuzzyRule 69 | fuzzyRuleArray *fuzzyRules; 70 | 71 | // PRIVATE METHODS 72 | void cleanFuzzyInputs(fuzzyInputArray *aux); 73 | void cleanFuzzyOutputs(fuzzyOutputArray *aux); 74 | void cleanFuzzyRules(fuzzyRuleArray *aux); 75 | }; 76 | #endif -------------------------------------------------------------------------------- /FuzzyRuleConsequent.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | * Robotic Research Group (RRG) 3 | * State University of Piauí (UESPI), Brazil - Piauí - Teresina 4 | * 5 | * FuzzyRuleConsequent.cpp 6 | * 7 | * Author: AJ Alves 8 | * Co authors: Dr. Ricardo Lira 9 | * Msc. Marvin Lemos 10 | * Douglas S. Kridi 11 | * Kannya Leal 12 | */ 13 | #include "FuzzyRuleConsequent.h" 14 | 15 | // CONTRUCTORS 16 | FuzzyRuleConsequent::FuzzyRuleConsequent() 17 | { 18 | this->fuzzySetOutputs = NULL; 19 | } 20 | 21 | // DESTRUCTOR 22 | FuzzyRuleConsequent::~FuzzyRuleConsequent() 23 | { 24 | this->cleanFuzzySets(this->fuzzySetOutputs); 25 | } 26 | 27 | // PUBLIC METHODS 28 | 29 | // Method to include a new FuzzySet (for Output) into FuzzyRuleConsequent 30 | bool FuzzyRuleConsequent::addOutput(FuzzySet *fuzzySet) 31 | { 32 | // auxiliary variable to handle the operation 33 | fuzzySetOutputArray *newOne; 34 | // allocating in memory 35 | if ((newOne = (fuzzySetOutputArray *)malloc(sizeof(fuzzySetOutputArray))) == NULL) 36 | { 37 | // return false if in out of memory 38 | return false; 39 | } 40 | // building the object 41 | newOne->fuzzySet = fuzzySet; 42 | newOne->next = NULL; 43 | // if it is the first FuzzySet (for Output), set it as the head 44 | if (this->fuzzySetOutputs == NULL) 45 | { 46 | this->fuzzySetOutputs = newOne; 47 | } 48 | else 49 | { 50 | // auxiliary variable to handle the operation 51 | fuzzySetOutputArray *aux = this->fuzzySetOutputs; 52 | // find the last element of the array 53 | while (aux != NULL) 54 | { 55 | if (aux->next == NULL) 56 | { 57 | // make the relations between them 58 | aux->next = newOne; 59 | return true; 60 | } 61 | aux = aux->next; 62 | } 63 | } 64 | return true; 65 | } 66 | 67 | // Method to evaluate this FuzzyRuleConsequent 68 | bool FuzzyRuleConsequent::evaluate(float power) 69 | { 70 | // auxiliary variable to handle the operation 71 | fuzzySetOutputArray *aux = this->fuzzySetOutputs; 72 | // while not in the end of the array, iterate 73 | while (aux != NULL) 74 | { 75 | // set the pertinence of each FuzzySet with the power 76 | aux->fuzzySet->setPertinence(power); 77 | aux = aux->next; 78 | } 79 | return true; 80 | } 81 | 82 | // PRIVATE METHODS 83 | 84 | // Method to recursively clean all fuzzySetOutputArray from memory 85 | void FuzzyRuleConsequent::cleanFuzzySets(fuzzySetOutputArray *aux) 86 | { 87 | if (aux != NULL) 88 | { 89 | this->cleanFuzzySets(aux->next); 90 | // emptying allocated memory 91 | free(aux); 92 | } 93 | } -------------------------------------------------------------------------------- /FuzzyIO.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | * Robotic Research Group (RRG) 3 | * State University of Piauí (UESPI), Brazil - Piauí - Teresina 4 | * 5 | * FuzzyIO.cpp 6 | * 7 | * Author: AJ Alves 8 | * Co authors: Dr. Ricardo Lira 9 | * Msc. Marvin Lemos 10 | * Douglas S. Kridi 11 | * Kannya Leal 12 | */ 13 | #include "FuzzyIO.h" 14 | 15 | // CONTRUCTORS 16 | FuzzyIO::FuzzyIO() 17 | { 18 | } 19 | 20 | FuzzyIO::FuzzyIO(int index) 21 | { 22 | this->index = index; 23 | this->crispInput = 0.0; 24 | // Initializing pointers with NULL 25 | this->fuzzySets = NULL; 26 | } 27 | 28 | // DESTRUCTOR 29 | FuzzyIO::~FuzzyIO() 30 | { 31 | this->cleanFuzzySets(this->fuzzySets); 32 | } 33 | 34 | // PUBLIC METHODS 35 | 36 | // Method to get the value of index 37 | int FuzzyIO::getIndex() 38 | { 39 | return this->index; 40 | } 41 | 42 | // Method to set the value of crispInput 43 | void FuzzyIO::setCrispInput(float crispInput) 44 | { 45 | this->crispInput = crispInput; 46 | } 47 | 48 | // Method to get the value of crispInput 49 | float FuzzyIO::getCrispInput() 50 | { 51 | return this->crispInput; 52 | } 53 | 54 | // Method to include a new FuzzySet into FuzzyIO 55 | bool FuzzyIO::addFuzzySet(FuzzySet *fuzzySet) 56 | { 57 | // auxiliary variable to handle the operation 58 | fuzzySetArray *newOne; 59 | // allocating in memory 60 | if ((newOne = (fuzzySetArray *)malloc(sizeof(fuzzySetArray))) == NULL) 61 | { 62 | // return false if in out of memory 63 | return false; 64 | } 65 | // building the object 66 | newOne->fuzzySet = fuzzySet; 67 | newOne->next = NULL; 68 | // if it is the first FuzzySet, set it as the head 69 | if (this->fuzzySets == NULL) 70 | { 71 | this->fuzzySets = newOne; 72 | } 73 | else 74 | { 75 | // auxiliary variable to handle the operation 76 | fuzzySetArray *aux = this->fuzzySets; 77 | // find the last element of the array 78 | while (aux != NULL) 79 | { 80 | if (aux->next == NULL) 81 | { 82 | // make the relations between them 83 | aux->next = newOne; 84 | return true; 85 | } 86 | aux = aux->next; 87 | } 88 | } 89 | return true; 90 | } 91 | 92 | // Method to reset all FuzzySet of this collection 93 | void FuzzyIO::resetFuzzySets() 94 | { 95 | // auxiliary variable to handle the operation 96 | fuzzySetArray *fuzzySetsAux = this->fuzzySets; 97 | // while not in the end of the array, iterate 98 | while (fuzzySetsAux != NULL) 99 | { 100 | fuzzySetsAux->fuzzySet->reset(); 101 | fuzzySetsAux = fuzzySetsAux->next; 102 | } 103 | } 104 | 105 | // PROTECTED METHODS 106 | 107 | // Method to recursively clean all FuzzySet from memory 108 | void FuzzyIO::cleanFuzzySets(fuzzySetArray *aux) 109 | { 110 | if (aux != NULL) 111 | { 112 | this->cleanFuzzySets(aux->next); 113 | // emptying allocated memory 114 | free(aux); 115 | } 116 | } -------------------------------------------------------------------------------- /FuzzySet.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | * Robotic Research Group (RRG) 3 | * State University of Piauí (UESPI), Brazil - Piauí - Teresina 4 | * 5 | * FuzzySet.cpp 6 | * 7 | * Author: AJ Alves 8 | * Co authors: Dr. Ricardo Lira 9 | * Msc. Marvin Lemos 10 | * Douglas S. Kridi 11 | * Kannya Leal 12 | */ 13 | #include "FuzzySet.h" 14 | 15 | // CONTRUCTORS 16 | FuzzySet::FuzzySet() 17 | { 18 | } 19 | 20 | FuzzySet::FuzzySet(float a, float b, float c, float d) 21 | { 22 | this->a = a; 23 | this->b = b; 24 | this->c = c; 25 | this->d = d; 26 | this->pertinence = 0.0; 27 | } 28 | 29 | // PUBLIC METHODS 30 | 31 | // Method to get the value of point A 32 | float FuzzySet::getPointA() 33 | { 34 | return this->a; 35 | } 36 | 37 | // Method to get the value of point B 38 | float FuzzySet::getPointB() 39 | { 40 | return this->b; 41 | } 42 | 43 | // Method to get the value of point C 44 | float FuzzySet::getPointC() 45 | { 46 | return this->c; 47 | } 48 | 49 | // Method to get the value of point D 50 | float FuzzySet::getPointD() 51 | { 52 | return this->d; 53 | } 54 | 55 | // Method to calculate the pertinence of the FuzzySet, according with the crispValue 56 | bool FuzzySet::calculatePertinence(float crispValue) 57 | { 58 | // check the crispValue is small then A 59 | if (crispValue < this->a) 60 | { 61 | // check if this FuzzySet represents "everithing small is true" 62 | if (this->a == this->b && this->b != this->c && this->c != this->d) 63 | { 64 | // if so, the pertinence is 1 65 | this->pertinence = 1.0; 66 | } 67 | else 68 | { 69 | // else, pertinence is 0 70 | this->pertinence = 0.0; 71 | } 72 | } 73 | // check if the crispValue is between A and B 74 | else if (crispValue >= this->a && crispValue < this->b) 75 | { 76 | // calculate a slope 77 | float slope = 1.0 / (this->b - this->a); 78 | // calculate the value of pertinence 79 | this->pertinence = slope * (crispValue - this->b) + 1.0; 80 | } 81 | // check if the pertinence is between B and C 82 | else if (crispValue >= this->b && crispValue <= this->c) 83 | { 84 | this->pertinence = 1.0; 85 | } 86 | // check if the pertinence is between C and D 87 | else if (crispValue > this->c && crispValue <= this->d) 88 | { 89 | // calculate a slope 90 | float slope = 1.0 / (this->c - this->d); 91 | // calculate the value of pertinence 92 | this->pertinence = slope * (crispValue - this->c) + 1.0; 93 | } 94 | // check the crispValue is bigger then D 95 | else if (crispValue > this->d) 96 | { 97 | // check if this FuzzySet represents "everithing bigger is true" 98 | if (this->c == this->d && this->c != this->b && this->b != this->a) 99 | { 100 | // if so, the pertinence is 1 101 | this->pertinence = 1.0; 102 | } 103 | else 104 | { 105 | // else, pertinence is 0 106 | this->pertinence = 0.0; 107 | } 108 | } 109 | return true; 110 | } 111 | 112 | // Method to set the value of pertinence 113 | void FuzzySet::setPertinence(float pertinence) 114 | { 115 | // check if the new pertinence is bigger then the current value because it can be called more then once by different FuzzyRuleConsequent 116 | if (this->pertinence < pertinence) 117 | { 118 | this->pertinence = pertinence; 119 | } 120 | } 121 | 122 | // Method to get the value of pertinence 123 | float FuzzySet::getPertinence() 124 | { 125 | return this->pertinence; 126 | } 127 | 128 | // Method to reset the value of pertinence 129 | void FuzzySet::reset() 130 | { 131 | this->pertinence = 0.0; 132 | } -------------------------------------------------------------------------------- /examples/arduino_simple_sample/arduino_simple_sample.ino: -------------------------------------------------------------------------------- 1 | #include 2 | 3 | // Instantiating a Fuzzy object 4 | Fuzzy *fuzzy = new Fuzzy(); 5 | 6 | void setup() 7 | { 8 | // Set the Serial output 9 | Serial.begin(9600); 10 | // Set a random seed 11 | randomSeed(analogRead(0)); 12 | 13 | // Instantiating a FuzzyInput object 14 | FuzzyInput *distance = new FuzzyInput(1); 15 | // Instantiating a FuzzySet object 16 | FuzzySet *small = new FuzzySet(0, 20, 20, 40); 17 | // Including the FuzzySet into FuzzyInput 18 | distance->addFuzzySet(small); 19 | // Instantiating a FuzzySet object 20 | FuzzySet *safe = new FuzzySet(30, 50, 50, 70); 21 | // Including the FuzzySet into FuzzyInput 22 | distance->addFuzzySet(safe); 23 | // Instantiating a FuzzySet object 24 | FuzzySet *big = new FuzzySet(60, 80, 80, 80); 25 | // Including the FuzzySet into FuzzyInput 26 | distance->addFuzzySet(big); 27 | // Including the FuzzyInput into Fuzzy 28 | fuzzy->addFuzzyInput(distance); 29 | 30 | // Instantiating a FuzzyOutput objects 31 | FuzzyOutput *speed = new FuzzyOutput(1); 32 | // Instantiating a FuzzySet object 33 | FuzzySet *slow = new FuzzySet(0, 10, 10, 20); 34 | // Including the FuzzySet into FuzzyOutput 35 | speed->addFuzzySet(slow); 36 | // Instantiating a FuzzySet object 37 | FuzzySet *average = new FuzzySet(10, 20, 30, 40); 38 | // Including the FuzzySet into FuzzyOutput 39 | speed->addFuzzySet(average); 40 | // Instantiating a FuzzySet object 41 | FuzzySet *fast = new FuzzySet(30, 40, 40, 50); 42 | // Including the FuzzySet into FuzzyOutput 43 | speed->addFuzzySet(fast); 44 | // Including the FuzzyOutput into Fuzzy 45 | fuzzy->addFuzzyOutput(speed); 46 | 47 | // Building FuzzyRule "IF distance = small THEN speed = slow" 48 | // Instantiating a FuzzyRuleAntecedent objects 49 | FuzzyRuleAntecedent *ifDistanceSmall = new FuzzyRuleAntecedent(); 50 | // Creating a FuzzyRuleAntecedent with just a single FuzzySet 51 | ifDistanceSmall->joinSingle(small); 52 | // Instantiating a FuzzyRuleConsequent objects 53 | FuzzyRuleConsequent *thenSpeedSlow = new FuzzyRuleConsequent(); 54 | // Including a FuzzySet to this FuzzyRuleConsequent 55 | thenSpeedSlow->addOutput(slow); 56 | // Instantiating a FuzzyRule objects 57 | FuzzyRule *fuzzyRule01 = new FuzzyRule(1, ifDistanceSmall, thenSpeedSlow); 58 | // Including the FuzzyRule into Fuzzy 59 | fuzzy->addFuzzyRule(fuzzyRule01); 60 | 61 | // Building FuzzyRule "IF distance = safe THEN speed = average" 62 | // Instantiating a FuzzyRuleAntecedent objects 63 | FuzzyRuleAntecedent *ifDistanceSafe = new FuzzyRuleAntecedent(); 64 | // Creating a FuzzyRuleAntecedent with just a single FuzzySet 65 | ifDistanceSafe->joinSingle(safe); 66 | // Instantiating a FuzzyRuleConsequent objects 67 | FuzzyRuleConsequent *thenSpeedAverage = new FuzzyRuleConsequent(); 68 | // Including a FuzzySet to this FuzzyRuleConsequent 69 | thenSpeedAverage->addOutput(average); 70 | // Instantiating a FuzzyRule objects 71 | FuzzyRule *fuzzyRule02 = new FuzzyRule(2, ifDistanceSafe, thenSpeedAverage); 72 | // Including the FuzzyRule into Fuzzy 73 | fuzzy->addFuzzyRule(fuzzyRule02); 74 | 75 | // Building FuzzyRule "IF distance = big THEN speed = high" 76 | // Instantiating a FuzzyRuleAntecedent objects 77 | FuzzyRuleAntecedent *ifDistanceBig = new FuzzyRuleAntecedent(); 78 | // Creating a FuzzyRuleAntecedent with just a single FuzzySet 79 | ifDistanceBig->joinSingle(big); 80 | // Instantiating a FuzzyRuleConsequent objects 81 | FuzzyRuleConsequent *thenSpeedFast = new FuzzyRuleConsequent(); 82 | // Including a FuzzySet to this FuzzyRuleConsequent 83 | thenSpeedFast->addOutput(fast); 84 | // Instantiating a FuzzyRule objects 85 | FuzzyRule *fuzzyRule03 = new FuzzyRule(3, ifDistanceBig, thenSpeedFast); 86 | // Including the FuzzyRule into Fuzzy 87 | fuzzy->addFuzzyRule(fuzzyRule03); 88 | } 89 | 90 | void loop() 91 | { 92 | // Getting a random value 93 | int input = random(0, 80); 94 | // Printing something 95 | Serial.println("\n\n\nEntrance: "); 96 | Serial.print("\t\t\tDistance: "); 97 | Serial.println(input); 98 | // Set the random value as an input 99 | fuzzy->setInput(1, input); 100 | // Running the Fuzzification 101 | fuzzy->fuzzify(); 102 | // Running the Defuzzification 103 | float output = fuzzy->defuzzify(1); 104 | // Printing something 105 | Serial.println("Result: "); 106 | Serial.print("\t\t\tSpeed: "); 107 | Serial.println(output); 108 | // wait 12 seconds 109 | delay(12000); 110 | } 111 | -------------------------------------------------------------------------------- /examples/general_simple_sample/general_simple_sample.cpp: -------------------------------------------------------------------------------- 1 | #include 2 | #include 3 | #include "../../Fuzzy.h" 4 | 5 | using namespace std; 6 | 7 | int random(int from, int to) 8 | { 9 | return (rand() % (to - from)) + from; 10 | } 11 | 12 | int main(int argc, char *argv[]) 13 | { 14 | // Set a seed to rand 15 | srand((unsigned)time(0)); 16 | 17 | // Instantiating a Fuzzy object 18 | Fuzzy *fuzzy = new Fuzzy(); 19 | 20 | // Instantiating a FuzzyInput object 21 | FuzzyInput *distance = new FuzzyInput(1); 22 | // Instantiating a FuzzySet object 23 | FuzzySet *small = new FuzzySet(0, 20, 20, 40); 24 | // Including the FuzzySet into FuzzyInput 25 | distance->addFuzzySet(small); 26 | // Instantiating a FuzzySet object 27 | FuzzySet *safe = new FuzzySet(30, 50, 50, 70); 28 | // Including the FuzzySet into FuzzyInput 29 | distance->addFuzzySet(safe); 30 | // Instantiating a FuzzySet object 31 | FuzzySet *big = new FuzzySet(60, 80, 80, 80); 32 | // Including the FuzzySet into FuzzyInput 33 | distance->addFuzzySet(big); 34 | // Including the FuzzyInput into Fuzzy 35 | fuzzy->addFuzzyInput(distance); 36 | 37 | // Instantiating a FuzzyOutput objects 38 | FuzzyOutput *speed = new FuzzyOutput(1); 39 | // Instantiating a FuzzySet object 40 | FuzzySet *slow = new FuzzySet(0, 10, 10, 20); 41 | // Including the FuzzySet into FuzzyOutput 42 | speed->addFuzzySet(slow); 43 | // Instantiating a FuzzySet object 44 | FuzzySet *average = new FuzzySet(10, 20, 30, 40); 45 | // Including the FuzzySet into FuzzyOutput 46 | speed->addFuzzySet(average); 47 | // Instantiating a FuzzySet object 48 | FuzzySet *fast = new FuzzySet(30, 40, 40, 50); 49 | // Including the FuzzySet into FuzzyOutput 50 | speed->addFuzzySet(fast); 51 | // Including the FuzzyOutput into Fuzzy 52 | fuzzy->addFuzzyOutput(speed); 53 | 54 | // Building FuzzyRule "IF distance = small THEN speed = slow" 55 | // Instantiating a FuzzyRuleAntecedent objects 56 | FuzzyRuleAntecedent *ifDistanceSmall = new FuzzyRuleAntecedent(); 57 | // Creating a FuzzyRuleAntecedent with just a single FuzzySet 58 | ifDistanceSmall->joinSingle(small); 59 | // Instantiating a FuzzyRuleConsequent objects 60 | FuzzyRuleConsequent *thenSpeedSlow = new FuzzyRuleConsequent(); 61 | // Including a FuzzySet to this FuzzyRuleConsequent 62 | thenSpeedSlow->addOutput(slow); 63 | // Instantiating a FuzzyRule objects 64 | FuzzyRule *fuzzyRule01 = new FuzzyRule(1, ifDistanceSmall, thenSpeedSlow); 65 | // Including the FuzzyRule into Fuzzy 66 | fuzzy->addFuzzyRule(fuzzyRule01); 67 | 68 | // Building FuzzyRule "IF distance = safe THEN speed = average" 69 | // Instantiating a FuzzyRuleAntecedent objects 70 | FuzzyRuleAntecedent *ifDistanceSafe = new FuzzyRuleAntecedent(); 71 | // Creating a FuzzyRuleAntecedent with just a single FuzzySet 72 | ifDistanceSafe->joinSingle(safe); 73 | // Instantiating a FuzzyRuleConsequent objects 74 | FuzzyRuleConsequent *thenSpeedAverage = new FuzzyRuleConsequent(); 75 | // Including a FuzzySet to this FuzzyRuleConsequent 76 | thenSpeedAverage->addOutput(average); 77 | // Instantiating a FuzzyRule objects 78 | FuzzyRule *fuzzyRule02 = new FuzzyRule(2, ifDistanceSafe, thenSpeedAverage); 79 | // Including the FuzzyRule into Fuzzy 80 | fuzzy->addFuzzyRule(fuzzyRule02); 81 | 82 | // Building FuzzyRule "IF distance = big THEN speed = high" 83 | // Instantiating a FuzzyRuleAntecedent objects 84 | FuzzyRuleAntecedent *ifDistanceBig = new FuzzyRuleAntecedent(); 85 | // Creating a FuzzyRuleAntecedent with just a single FuzzySet 86 | ifDistanceBig->joinSingle(big); 87 | // Instantiating a FuzzyRuleConsequent objects 88 | FuzzyRuleConsequent *thenSpeedFast = new FuzzyRuleConsequent(); 89 | // Including a FuzzySet to this FuzzyRuleConsequent 90 | thenSpeedFast->addOutput(fast); 91 | // Instantiating a FuzzyRule objects 92 | FuzzyRule *fuzzyRule03 = new FuzzyRule(3, ifDistanceBig, thenSpeedFast); 93 | // Including the FuzzyRule into Fuzzy 94 | fuzzy->addFuzzyRule(fuzzyRule03); 95 | 96 | // get a random value 97 | int input = random(0, 100); 98 | // Printing something 99 | cout << "\n\n\nEntrance: \n\t\t\tDistance: " << input << endl; 100 | // Set the random value as an input 101 | fuzzy->setInput(1, input); 102 | // Running the Fuzzification 103 | fuzzy->fuzzify(); 104 | // Running the Defuzzification 105 | float output = fuzzy->defuzzify(1); 106 | // Printing something 107 | cout << "Result: \n\t\t\tSpeed: " << output << endl; 108 | return 0; 109 | } -------------------------------------------------------------------------------- /README.md: -------------------------------------------------------------------------------- 1 | ![GitHub tag (latest SemVer)](https://img.shields.io/github/tag/zerokol/eFLL.svg) 2 | ![GitHub](https://img.shields.io/github/license/zerokol/eFLL.svg) 3 | [![Codacy Badge](https://app.codacy.com/project/badge/Grade/cf8ec18693d54d0d9437e4f198339195)](https://www.codacy.com/gh/zerokol/eFLL/dashboard?utm_source=github.com&utm_medium=referral&utm_content=zerokol/eFLL&utm_campaign=Badge_Grade) 4 | ![GitHub top language](https://img.shields.io/github/languages/top/zerokol/eFLL.svg) 5 | ![GitHub search hit counter](https://img.shields.io/github/search/zerokol/eFLL/fuzzy.svg) 6 | ![GitHub last commit (branch)](https://img.shields.io/github/last-commit/zerokol/eFLL/master.svg) 7 | 8 | ## eFLL (Embedded Fuzzy Logic Library) 9 | 10 | eFLL (Embedded Fuzzy Logic Library) is a standard library for Embedded Systems to implement easy and efficient Fuzzy Systems. 11 | 12 | Para informações avançadas, documentação e exemplos de uso em PORTUGUÊS: [eFLL - Uma Biblioteca Fuzzy para Arduino e Sistemas Embarcados](https://blog.alvesoaj.com/2012/09/arduinofuzzy-uma-biblioteca-fuzzy-para.html) 13 | 14 | For advanced information, documentation, and usage examples in ENGLISH: [eFLL - A Fuzzy Library for Arduino and Embedded Systems](https://blog.alvesoaj.com/2012/09/arduinofuzzy-fuzzy-library-for-arduino.html) 15 | 16 | ## Characteristics 17 | 18 | Written in C++/C, uses only standard C language library "stdlib.h", so eFLL is a library designed not only to Arduino, but any Embedded System or not how have your commands written in C. 19 | 20 | It has no explicit limitations on quantity of Fuzzy, Fuzzy Rules, Inputs or Outputs, these limited processing power and storage of each microcontroller 21 | 22 | It uses the process: 23 | 24 | (MAX-MIN) and (Mamdani Minimum) for inference and composition, (CENTER OF AREA) to defuzzification in a continuous universe. 25 | 26 | Tested with [GTest](http://code.google.com/p/googletest/) for C, Google Inc. 27 | 28 | ## How to install (general use) 29 | 30 | **Step 1:** Go to the official project page on GitHub (Here) 31 | 32 | **Step 2:** Make a clone of the project using Git or download at Download on the button "Download as zip." 33 | 34 | **Step 3:** Clone or unzip (For safety, rename the folder to "eFLL") the files into some folder 35 | 36 | **Step 4:** Compile and link it to your code (See Makefile) 37 | 38 | ## How to install (and import to use with Arduino) 39 | 40 | ### Easy Way 41 | 42 | **Step 1:** Open the Arduino IDE 43 | 44 | **Step 2:** In main menu, go to SKETCH >> INCLUDE LIBRARY >> MANAGE LIBRARIES 45 | 46 | **Step 3:** Search for "eFLL" or "Fuzzy" 47 | 48 | **Step 4:** eFLL will appear in the list, to finish, just click in INSTALL, now you can include eFLL to your sketchs 49 | 50 | ### Old Way 51 | 52 | **Step 1:** Go to the official project page on GitHub (Here) 53 | 54 | **Step 2:** Make a clone of the project using Git or download at Download on the button "Download as zip." 55 | 56 | **Step 3:** Clone or unzip (For safety, rename the folder to "eFLL") the files into Arduino libraries' folder: 57 | 58 | Ubuntu (/usr/share/arduino/libraries/) if installed via apt-get, if not, on Windows, Mac or Linux (where you downloaded the Arduino IDE, the Library folder is inside) 59 | 60 | **Ok! The library is ready to be used!** 61 | 62 | If the installation of the library has been successfully held, to import the library is easy: 63 | 64 | **Step 4:** Open your Arduino IDE, check out the tab on the top menu SKETCH → LIBRARY → Import eFLL 65 | 66 | ## Brief Documentation 67 | 68 | ![Class Diagram](https://raw.githubusercontent.com/zerokol/eFLL/master/uml/class-diagram.png) 69 | 70 | **Fuzzy object** - This object includes all the Fuzzy System, through it, you can manipulate the Fuzzy Sets, Linguistic Rules, inputs and outputs. 71 | 72 | **FuzzyInput** object - This object groups all entries Fuzzy Sets that belongs to the same domain. 73 | 74 | **FuzzyOutput** object - This object is similar to FuzzyInput, is used to group all output Fuzzy Sets thar belongs to the same domain. 75 | 76 | **FuzzySet** object - This is one of the main objects of Fuzzy Library, with each set is possible to model the system in question. Currently the library supports triangular membership functions, trapezoidal and singleton, which are assembled based on points A, B, C and D, they are passed by parameter in its constructor FuzzySet(float a, float b, float c, float d). 77 | 78 | **FuzzyRule** object - This object is used to mount the base rule of Fuzzy object, which contains one or more of this object. Instantiated with FuzzyRule fr = new FuzzyRule (ID, antecedent, consequent). 79 | 80 | **FuzzyRuleAntecedent** object - This object is used to compound the object FuzzyRule, responsible for assembling the antecedent of the conditional expression of a FuzzyRule. 81 | 82 | **FuzzyRuleConsequent** object - This object is used to render the object FuzzyRule, responsible for assembling the output expression of a FuzzyRule. 83 | 84 | ## Tips 85 | 86 | These are all eFLL library objects that are used in the process. The next step, generally interactive is handled by three methods of the Fuzzy Class first: 87 | 88 | `bool setInput(int id, float value);` 89 | 90 | It is used to pass the Crispe input value to the system note that the first parameter is the FuzzyInput object' ID which parameter value is intended. 91 | 92 | `bool fuzzify();` 93 | 94 | It is used to start the fuzzification process, composition and inference. 95 | 96 | And finally: 97 | 98 | `float defuzzify(int id);` 99 | 100 | ## REFERENCES 101 | 102 | **Authors:** AJ Alves ; **Co authors:** Dr. Ricardo Lira , Msc. Marvin Lemos , Douglas S. Kridi , Kannya Leal 103 | 104 | ## Special Thanks to Contributors 105 | 106 | [@mikebutrimov](https://github.com/mikebutrimov), [@tzikis](https://github.com/tzikis), [@na7an](https://github.com/na7an) 107 | 108 | ## LICENSE 109 | 110 | MIT License 111 | -------------------------------------------------------------------------------- /examples/general_advanced_sample/general_advanced_sample.cpp: -------------------------------------------------------------------------------- 1 | #include 2 | #include 3 | #include "../../Fuzzy.h" 4 | 5 | using namespace std; 6 | 7 | int random(int from, int to) 8 | { 9 | return (rand() % (to - from)) + from; 10 | } 11 | 12 | int main(int argc, char *argv[]) 13 | { 14 | // Set a seed to rand 15 | srand((unsigned)time(0)); 16 | 17 | Fuzzy *fuzzy = new Fuzzy(); 18 | 19 | // FuzzyInput 20 | FuzzyInput *distance = new FuzzyInput(1); 21 | 22 | FuzzySet *near = new FuzzySet(0, 20, 20, 40); 23 | distance->addFuzzySet(near); 24 | FuzzySet *safe = new FuzzySet(30, 50, 50, 70); 25 | distance->addFuzzySet(safe); 26 | FuzzySet *distant = new FuzzySet(60, 80, 100, 100); 27 | distance->addFuzzySet(distant); 28 | 29 | fuzzy->addFuzzyInput(distance); 30 | 31 | // FuzzyInput 32 | FuzzyInput *inputSpeed = new FuzzyInput(2); 33 | 34 | FuzzySet *stopedInput = new FuzzySet(0, 0, 0, 0); 35 | inputSpeed->addFuzzySet(stopedInput); 36 | FuzzySet *slowInput = new FuzzySet(1, 10, 10, 20); 37 | inputSpeed->addFuzzySet(slowInput); 38 | FuzzySet *normalInput = new FuzzySet(15, 30, 30, 50); 39 | inputSpeed->addFuzzySet(normalInput); 40 | FuzzySet *quickInput = new FuzzySet(45, 60, 70, 70); 41 | inputSpeed->addFuzzySet(quickInput); 42 | 43 | fuzzy->addFuzzyInput(inputSpeed); 44 | 45 | // FuzzyInput 46 | FuzzyInput *temperature = new FuzzyInput(3); 47 | 48 | FuzzySet *cold = new FuzzySet(-30, -30, -20, -10); 49 | temperature->addFuzzySet(cold); 50 | FuzzySet *good = new FuzzySet(-15, 0, 0, 15); 51 | temperature->addFuzzySet(good); 52 | FuzzySet *hot = new FuzzySet(10, 20, 30, 30); 53 | temperature->addFuzzySet(hot); 54 | 55 | fuzzy->addFuzzyInput(temperature); 56 | 57 | // FuzzyOutput 58 | FuzzyOutput *risk = new FuzzyOutput(1); 59 | 60 | FuzzySet *minimum = new FuzzySet(0, 20, 20, 40); 61 | risk->addFuzzySet(minimum); 62 | FuzzySet *average = new FuzzySet(30, 50, 50, 70); 63 | risk->addFuzzySet(average); 64 | FuzzySet *maximum = new FuzzySet(60, 80, 80, 100); 65 | risk->addFuzzySet(maximum); 66 | 67 | fuzzy->addFuzzyOutput(risk); 68 | 69 | // FuzzyOutput 70 | FuzzyOutput *speedOutput = new FuzzyOutput(2); 71 | 72 | FuzzySet *stopedOutput = new FuzzySet(0, 0, 0, 0); 73 | speedOutput->addFuzzySet(stopedOutput); 74 | FuzzySet *slowOutput = new FuzzySet(1, 10, 10, 20); 75 | speedOutput->addFuzzySet(slowOutput); 76 | FuzzySet *normalOutput = new FuzzySet(15, 30, 30, 50); 77 | speedOutput->addFuzzySet(normalOutput); 78 | FuzzySet *quickOutput = new FuzzySet(45, 60, 70, 70); 79 | speedOutput->addFuzzySet(quickOutput); 80 | 81 | fuzzy->addFuzzyOutput(speedOutput); 82 | 83 | // Building FuzzyRule 84 | FuzzyRuleAntecedent *distanceCloseAndSpeedQuick = new FuzzyRuleAntecedent(); 85 | distanceCloseAndSpeedQuick->joinWithAND(near, quickInput); 86 | FuzzyRuleAntecedent *temperatureCold = new FuzzyRuleAntecedent(); 87 | temperatureCold->joinSingle(cold); 88 | FuzzyRuleAntecedent *ifDistanceCloseAndSpeedQuickOrTemperatureCold = new FuzzyRuleAntecedent(); 89 | ifDistanceCloseAndSpeedQuickOrTemperatureCold->joinWithOR(distanceCloseAndSpeedQuick, temperatureCold); 90 | 91 | FuzzyRuleConsequent *thenRisMaximumAndSpeedSlow = new FuzzyRuleConsequent(); 92 | thenRisMaximumAndSpeedSlow->addOutput(maximum); 93 | thenRisMaximumAndSpeedSlow->addOutput(slowOutput); 94 | 95 | FuzzyRule *fuzzyRule1 = new FuzzyRule(1, ifDistanceCloseAndSpeedQuickOrTemperatureCold, thenRisMaximumAndSpeedSlow); 96 | fuzzy->addFuzzyRule(fuzzyRule1); 97 | 98 | // Building FuzzyRule 99 | FuzzyRuleAntecedent *distanceSafeAndSpeedNormal = new FuzzyRuleAntecedent(); 100 | distanceSafeAndSpeedNormal->joinWithAND(safe, normalInput); 101 | FuzzyRuleAntecedent *ifDistanceSafeAndSpeedNormalOrTemperatureGood = new FuzzyRuleAntecedent(); 102 | ifDistanceSafeAndSpeedNormalOrTemperatureGood->joinWithOR(distanceSafeAndSpeedNormal, good); 103 | 104 | FuzzyRuleConsequent *thenRiskAverageAndSpeedNormal = new FuzzyRuleConsequent(); 105 | thenRiskAverageAndSpeedNormal->addOutput(average); 106 | thenRiskAverageAndSpeedNormal->addOutput(normalOutput); 107 | 108 | FuzzyRule *fuzzyRule2 = new FuzzyRule(2, ifDistanceSafeAndSpeedNormalOrTemperatureGood, thenRiskAverageAndSpeedNormal); 109 | fuzzy->addFuzzyRule(fuzzyRule2); 110 | 111 | // Building FuzzyRule 112 | FuzzyRuleAntecedent *distanceDistantAndSpeedSlow = new FuzzyRuleAntecedent(); 113 | distanceDistantAndSpeedSlow->joinWithAND(distant, slowInput); 114 | FuzzyRuleAntecedent *ifDistanceDistantAndSpeedSlowOrTemperatureHot = new FuzzyRuleAntecedent(); 115 | ifDistanceDistantAndSpeedSlowOrTemperatureHot->joinWithOR(distanceDistantAndSpeedSlow, hot); 116 | 117 | FuzzyRuleConsequent *thenRiskMinimumSpeedQuick = new FuzzyRuleConsequent(); 118 | thenRiskMinimumSpeedQuick->addOutput(minimum); 119 | thenRiskMinimumSpeedQuick->addOutput(quickOutput); 120 | 121 | FuzzyRule *fuzzyRule3 = new FuzzyRule(3, ifDistanceDistantAndSpeedSlowOrTemperatureHot, thenRiskMinimumSpeedQuick); 122 | fuzzy->addFuzzyRule(fuzzyRule3); 123 | 124 | // get random entrances 125 | int input1 = random(0, 100); 126 | int input2 = random(0, 70); 127 | int input3 = random(-30, 30); 128 | 129 | cout << "\n\n\nEntrance: \n\t\t\tDistance: " << input1 << ", Speed: " << input2 << ", and Temperature: " << input3 << endl; 130 | 131 | fuzzy->setInput(1, input1); 132 | fuzzy->setInput(2, input2); 133 | fuzzy->setInput(3, input3); 134 | 135 | fuzzy->fuzzify(); 136 | 137 | cout << "Input: \n\tDistance: Near-> " << near->getPertinence() << ", Safe->" << safe->getPertinence() << ", Distant-> " << distant->getPertinence() << endl; 138 | cout << "\tSpeed: Stoped-> " << stopedInput->getPertinence() << ", Slow-> " << slowInput->getPertinence() << ", Normal-> " << normalInput->getPertinence() << ", Quick-> " << quickInput->getPertinence() << endl; 139 | cout << "\tTemperature: Cold->" << cold->getPertinence() << ", Good-> " << good->getPertinence() << ", Hot-> " << hot->getPertinence() << endl; 140 | 141 | cout << "Roles: \n\tRole01-> " << fuzzyRule1->isFired() << ", Role02-> " << fuzzyRule2->isFired() << ", Role03-> " << fuzzyRule3->isFired() << endl; 142 | 143 | float output1 = fuzzy->defuzzify(1); 144 | float output2 = fuzzy->defuzzify(2); 145 | 146 | cout << "Output: \n\tRisk: Minimum-> " << minimum->getPertinence() << ", Average->" << average->getPertinence() << ", Maximum-> " << maximum->getPertinence() << endl; 147 | cout << "\tSpeed: Stoped-> " << stopedOutput->getPertinence() << ", Slow-> " << slowOutput->getPertinence() << ", Normal-> " << normalOutput->getPertinence() << ", Quick-> " << quickOutput->getPertinence() << endl; 148 | 149 | cout << "Result: \n\t\t\tRisk: " << output1 << ", and Speed: " << output2 << endl; 150 | 151 | return 0; 152 | } -------------------------------------------------------------------------------- /examples/arduino_advanced_sample/arduino_advanced_sample.ino: -------------------------------------------------------------------------------- 1 | #include 2 | 3 | // For scope, instantiate all objects you will need to access in loop() 4 | // It may be just one Fuzzy, but for demonstration, this sample will print 5 | // all FuzzySet pertinence 6 | 7 | // Fuzzy 8 | Fuzzy *fuzzy = new Fuzzy(); 9 | 10 | // FuzzyInput 11 | FuzzySet *near = new FuzzySet(0, 20, 20, 40); 12 | FuzzySet *safe = new FuzzySet(30, 50, 50, 70); 13 | FuzzySet *distant = new FuzzySet(60, 80, 100, 100); 14 | 15 | // FuzzyInput 16 | FuzzySet *stopedInput = new FuzzySet(0, 0, 0, 0); 17 | FuzzySet *slowInput = new FuzzySet(1, 10, 10, 20); 18 | FuzzySet *normalInput = new FuzzySet(15, 30, 30, 50); 19 | FuzzySet *quickInput = new FuzzySet(45, 60, 70, 70); 20 | 21 | // FuzzyInput 22 | FuzzySet *cold = new FuzzySet(-30, -30, -20, -10); 23 | FuzzySet *good = new FuzzySet(-15, 0, 0, 15); 24 | FuzzySet *hot = new FuzzySet(10, 20, 30, 30); 25 | 26 | // FuzzyOutput 27 | FuzzySet *minimum = new FuzzySet(0, 20, 20, 40); 28 | FuzzySet *average = new FuzzySet(30, 50, 50, 70); 29 | FuzzySet *maximum = new FuzzySet(60, 80, 80, 100); 30 | 31 | // FuzzyOutput 32 | FuzzySet *stopedOutput = new FuzzySet(0, 0, 0, 0); 33 | FuzzySet *slowOutput = new FuzzySet(1, 10, 10, 20); 34 | FuzzySet *normalOutput = new FuzzySet(15, 30, 30, 50); 35 | FuzzySet *quickOutput = new FuzzySet(45, 60, 70, 70); 36 | 37 | void setup() 38 | { 39 | // Set the Serial output 40 | Serial.begin(9600); 41 | // Set a random seed 42 | randomSeed(analogRead(0)); 43 | 44 | // Every setup must occur in the function setup() 45 | 46 | // FuzzyInput 47 | FuzzyInput *distance = new FuzzyInput(1); 48 | 49 | distance->addFuzzySet(near); 50 | distance->addFuzzySet(safe); 51 | distance->addFuzzySet(distant); 52 | fuzzy->addFuzzyInput(distance); 53 | 54 | // FuzzyInput 55 | FuzzyInput *speedInput = new FuzzyInput(2); 56 | 57 | speedInput->addFuzzySet(stopedInput); 58 | speedInput->addFuzzySet(slowInput); 59 | speedInput->addFuzzySet(normalInput); 60 | speedInput->addFuzzySet(quickInput); 61 | fuzzy->addFuzzyInput(speedInput); 62 | 63 | // FuzzyInput 64 | FuzzyInput *temperature = new FuzzyInput(3); 65 | 66 | temperature->addFuzzySet(cold); 67 | temperature->addFuzzySet(good); 68 | temperature->addFuzzySet(hot); 69 | fuzzy->addFuzzyInput(temperature); 70 | 71 | // FuzzyOutput 72 | FuzzyOutput *risk = new FuzzyOutput(1); 73 | 74 | risk->addFuzzySet(minimum); 75 | risk->addFuzzySet(average); 76 | risk->addFuzzySet(maximum); 77 | fuzzy->addFuzzyOutput(risk); 78 | 79 | // FuzzyOutput 80 | FuzzyOutput *speedOutput = new FuzzyOutput(2); 81 | 82 | speedOutput->addFuzzySet(stopedOutput); 83 | speedOutput->addFuzzySet(slowOutput); 84 | speedOutput->addFuzzySet(normalOutput); 85 | speedOutput->addFuzzySet(quickOutput); 86 | fuzzy->addFuzzyOutput(speedOutput); 87 | 88 | // Building FuzzyRule 89 | FuzzyRuleAntecedent *distanceNearAndSpeedQuick = new FuzzyRuleAntecedent(); 90 | distanceNearAndSpeedQuick->joinWithAND(near, quickInput); 91 | FuzzyRuleAntecedent *temperatureCold = new FuzzyRuleAntecedent(); 92 | temperatureCold->joinSingle(cold); 93 | FuzzyRuleAntecedent *ifDistanceNearAndSpeedQuickOrTemperatureCold = new FuzzyRuleAntecedent(); 94 | ifDistanceNearAndSpeedQuickOrTemperatureCold->joinWithOR(distanceNearAndSpeedQuick, temperatureCold); 95 | 96 | FuzzyRuleConsequent *thenRisMaximumAndSpeedSlow = new FuzzyRuleConsequent(); 97 | thenRisMaximumAndSpeedSlow->addOutput(maximum); 98 | thenRisMaximumAndSpeedSlow->addOutput(slowOutput); 99 | 100 | FuzzyRule *fuzzyRule1 = new FuzzyRule(1, ifDistanceNearAndSpeedQuickOrTemperatureCold, thenRisMaximumAndSpeedSlow); 101 | fuzzy->addFuzzyRule(fuzzyRule1); 102 | 103 | // Building FuzzyRule 104 | FuzzyRuleAntecedent *distanceSafeAndSpeedNormal = new FuzzyRuleAntecedent(); 105 | distanceSafeAndSpeedNormal->joinWithAND(safe, normalInput); 106 | FuzzyRuleAntecedent *ifDistanceSafeAndSpeedNormalOrTemperatureGood = new FuzzyRuleAntecedent(); 107 | ifDistanceSafeAndSpeedNormalOrTemperatureGood->joinWithOR(distanceSafeAndSpeedNormal, good); 108 | 109 | FuzzyRuleConsequent *thenRiskAverageAndSpeedNormal = new FuzzyRuleConsequent(); 110 | thenRiskAverageAndSpeedNormal->addOutput(average); 111 | thenRiskAverageAndSpeedNormal->addOutput(normalOutput); 112 | 113 | FuzzyRule *fuzzyRule2 = new FuzzyRule(2, ifDistanceSafeAndSpeedNormalOrTemperatureGood, thenRiskAverageAndSpeedNormal); 114 | fuzzy->addFuzzyRule(fuzzyRule2); 115 | 116 | // Building FuzzyRule 117 | FuzzyRuleAntecedent *distanceDistantAndSpeedSlow = new FuzzyRuleAntecedent(); 118 | distanceDistantAndSpeedSlow->joinWithAND(distant, slowInput); 119 | FuzzyRuleAntecedent *ifDistanceDistantAndSpeedSlowOrTemperatureHot = new FuzzyRuleAntecedent(); 120 | ifDistanceDistantAndSpeedSlowOrTemperatureHot->joinWithOR(distanceDistantAndSpeedSlow, hot); 121 | 122 | FuzzyRuleConsequent *thenRiskMinimumSpeedQuick = new FuzzyRuleConsequent(); 123 | thenRiskMinimumSpeedQuick->addOutput(minimum); 124 | thenRiskMinimumSpeedQuick->addOutput(quickOutput); 125 | 126 | FuzzyRule *fuzzyRule3 = new FuzzyRule(3, ifDistanceDistantAndSpeedSlowOrTemperatureHot, thenRiskMinimumSpeedQuick); 127 | fuzzy->addFuzzyRule(fuzzyRule3); 128 | } 129 | 130 | void loop() 131 | { 132 | // get random entrances 133 | int input1 = random(0, 100); 134 | int input2 = random(0, 70); 135 | int input3 = random(-30, 30); 136 | 137 | Serial.println("\n\n\nEntrance: "); 138 | Serial.print("\t\t\tDistance: "); 139 | Serial.print(input1); 140 | Serial.print(", Speed: "); 141 | Serial.print(input2); 142 | Serial.print(", and Temperature: "); 143 | Serial.println(input3); 144 | 145 | fuzzy->setInput(1, input1); 146 | fuzzy->setInput(2, input2); 147 | fuzzy->setInput(3, input3); 148 | 149 | fuzzy->fuzzify(); 150 | 151 | Serial.println("Input: "); 152 | Serial.print("\tDistance: Near-> "); 153 | Serial.print(near->getPertinence()); 154 | Serial.print(", Safe-> "); 155 | Serial.print(safe->getPertinence()); 156 | Serial.print(", Distant-> "); 157 | Serial.println(distant->getPertinence()); 158 | 159 | Serial.print("\tSpeed: Stoped-> "); 160 | Serial.print(stopedInput->getPertinence()); 161 | Serial.print(", Slow-> "); 162 | Serial.print(slowInput->getPertinence()); 163 | Serial.print(", Normal-> "); 164 | Serial.print(normalInput->getPertinence()); 165 | Serial.print(", Quick-> "); 166 | Serial.println(quickInput->getPertinence()); 167 | 168 | Serial.print("\tTemperature: Cold-> "); 169 | Serial.print(cold->getPertinence()); 170 | Serial.print(", Good-> "); 171 | Serial.print(good->getPertinence()); 172 | Serial.print(", Hot-> "); 173 | Serial.println(hot->getPertinence()); 174 | 175 | float output1 = fuzzy->defuzzify(1); 176 | float output2 = fuzzy->defuzzify(2); 177 | 178 | Serial.println("Output: "); 179 | Serial.print("\tRisk: Minimum-> "); 180 | Serial.print(minimum->getPertinence()); 181 | Serial.print(", Average-> "); 182 | Serial.print(average->getPertinence()); 183 | Serial.print(", Maximum-> "); 184 | Serial.println(maximum->getPertinence()); 185 | 186 | Serial.print("\tSpeed: Stoped-> "); 187 | Serial.print(stopedOutput->getPertinence()); 188 | Serial.print(", Slow-> "); 189 | Serial.print(slowOutput->getPertinence()); 190 | Serial.print(", Normal-> "); 191 | Serial.print(normalOutput->getPertinence()); 192 | Serial.print(", Quick-> "); 193 | Serial.println(quickOutput->getPertinence()); 194 | 195 | Serial.println("Result: "); 196 | Serial.print("\t\t\tRisk: "); 197 | Serial.print(output1); 198 | Serial.print(", and Speed: "); 199 | Serial.println(output2); 200 | 201 | // wait 12 seconds 202 | delay(12000); 203 | } -------------------------------------------------------------------------------- /tests/GeneralTest.cpp: -------------------------------------------------------------------------------- 1 | #include 2 | #include 3 | #include "../Fuzzy.h" 4 | 5 | using namespace std; 6 | 7 | int main(int argc, char *argv[]) 8 | { 9 | Fuzzy *fuzzy = new Fuzzy(); 10 | 11 | // FuzzyInput 12 | FuzzyInput *temperature = new FuzzyInput(1); 13 | 14 | FuzzySet *veryLow = new FuzzySet(-5, -5, 0, 15); 15 | temperature->addFuzzySet(veryLow); 16 | FuzzySet *low = new FuzzySet(10, 20, 20, 30); 17 | temperature->addFuzzySet(low); 18 | FuzzySet *high = new FuzzySet(25, 30, 30, 35); 19 | temperature->addFuzzySet(high); 20 | FuzzySet *veryHigh = new FuzzySet(30, 45, 50, 50); 21 | temperature->addFuzzySet(veryHigh); 22 | 23 | fuzzy->addFuzzyInput(temperature); 24 | 25 | // FuzzyInput 26 | FuzzyInput *humidity = new FuzzyInput(2); 27 | 28 | FuzzySet *dry = new FuzzySet(-5, -5, 0, 30); 29 | humidity->addFuzzySet(dry); 30 | FuzzySet *comfortable = new FuzzySet(20, 35, 35, 50); 31 | humidity->addFuzzySet(comfortable); 32 | FuzzySet *humid = new FuzzySet(40, 55, 55, 70); 33 | humidity->addFuzzySet(humid); 34 | FuzzySet *sticky = new FuzzySet(60, 100, 105, 105); 35 | humidity->addFuzzySet(sticky); 36 | 37 | fuzzy->addFuzzyInput(humidity); 38 | 39 | // FuzzyOutput 40 | FuzzyOutput *speed = new FuzzyOutput(1); 41 | 42 | FuzzySet *off = new FuzzySet(0, 0, 0, 0); 43 | speed->addFuzzySet(off); 44 | FuzzySet *lowHumidity = new FuzzySet(30, 45, 45, 60); 45 | speed->addFuzzySet(lowHumidity); 46 | FuzzySet *medium = new FuzzySet(50, 65, 65, 80); 47 | speed->addFuzzySet(medium); 48 | FuzzySet *fast = new FuzzySet(70, 90, 95, 95); 49 | speed->addFuzzySet(fast); 50 | 51 | fuzzy->addFuzzyOutput(speed); 52 | 53 | // Building FuzzyRule 54 | FuzzyRuleAntecedent *ifVeryLowAndDry = new FuzzyRuleAntecedent(); 55 | ifVeryLowAndDry->joinWithAND(veryLow, dry); 56 | FuzzyRuleConsequent *thenOff1 = new FuzzyRuleConsequent(); 57 | thenOff1->addOutput(off); 58 | FuzzyRule *fuzzyRule1 = new FuzzyRule(1, ifVeryLowAndDry, thenOff1); 59 | fuzzy->addFuzzyRule(fuzzyRule1); 60 | 61 | // Building FuzzyRule 62 | FuzzyRuleAntecedent *ifVeryLowAndComfortable = new FuzzyRuleAntecedent(); 63 | ifVeryLowAndComfortable->joinWithAND(veryLow, comfortable); 64 | FuzzyRuleConsequent *thenOff2 = new FuzzyRuleConsequent(); 65 | thenOff2->addOutput(off); 66 | FuzzyRule *fuzzyRule2 = new FuzzyRule(2, ifVeryLowAndComfortable, thenOff2); 67 | fuzzy->addFuzzyRule(fuzzyRule2); 68 | 69 | // Building FuzzyRule 70 | FuzzyRuleAntecedent *ifVeryLowAndHumid = new FuzzyRuleAntecedent(); 71 | ifVeryLowAndHumid->joinWithAND(veryLow, humid); 72 | FuzzyRuleConsequent *thenOff3 = new FuzzyRuleConsequent(); 73 | thenOff3->addOutput(off); 74 | FuzzyRule *fuzzyRule3 = new FuzzyRule(3, ifVeryLowAndHumid, thenOff3); 75 | fuzzy->addFuzzyRule(fuzzyRule3); 76 | 77 | // Building FuzzyRule 78 | FuzzyRuleAntecedent *ifVeryLowAndSticky = new FuzzyRuleAntecedent(); 79 | ifVeryLowAndSticky->joinWithAND(veryLow, sticky); 80 | FuzzyRuleConsequent *thenLow1 = new FuzzyRuleConsequent(); 81 | thenLow1->addOutput(lowHumidity); 82 | FuzzyRule *fuzzyRule4 = new FuzzyRule(4, ifVeryLowAndSticky, thenLow1); 83 | fuzzy->addFuzzyRule(fuzzyRule4); 84 | 85 | // Building FuzzyRule 86 | FuzzyRuleAntecedent *ifLowAndDry = new FuzzyRuleAntecedent(); 87 | ifLowAndDry->joinWithAND(low, dry); 88 | FuzzyRuleConsequent *thenOff4 = new FuzzyRuleConsequent(); 89 | thenOff4->addOutput(off); 90 | FuzzyRule *fuzzyRule5 = new FuzzyRule(5, ifLowAndDry, thenOff4); 91 | fuzzy->addFuzzyRule(fuzzyRule5); 92 | 93 | // Building FuzzyRule 94 | FuzzyRuleAntecedent *ifLowAndComfortable = new FuzzyRuleAntecedent(); 95 | ifLowAndComfortable->joinWithAND(low, comfortable); 96 | FuzzyRuleConsequent *thenOff5 = new FuzzyRuleConsequent(); 97 | thenOff5->addOutput(off); 98 | FuzzyRule *fuzzyRule6 = new FuzzyRule(6, ifLowAndComfortable, thenOff5); 99 | fuzzy->addFuzzyRule(fuzzyRule6); 100 | 101 | // Building FuzzyRule 102 | FuzzyRuleAntecedent *ifLowAndHumid = new FuzzyRuleAntecedent(); 103 | ifLowAndHumid->joinWithAND(low, humid); 104 | FuzzyRuleConsequent *thenLow2 = new FuzzyRuleConsequent(); 105 | thenLow2->addOutput(lowHumidity); 106 | FuzzyRule *fuzzyRule7 = new FuzzyRule(7, ifLowAndHumid, thenLow2); 107 | fuzzy->addFuzzyRule(fuzzyRule7); 108 | 109 | // Building FuzzyRule 110 | FuzzyRuleAntecedent *ifLowAndSticky = new FuzzyRuleAntecedent(); 111 | ifLowAndSticky->joinWithAND(low, sticky); 112 | FuzzyRuleConsequent *thenMedium1 = new FuzzyRuleConsequent(); 113 | thenMedium1->addOutput(medium); 114 | FuzzyRule *fuzzyRule8 = new FuzzyRule(8, ifLowAndSticky, thenMedium1); 115 | fuzzy->addFuzzyRule(fuzzyRule8); 116 | 117 | // Building FuzzyRule 118 | FuzzyRuleAntecedent *ifHighAndDry = new FuzzyRuleAntecedent(); 119 | ifHighAndDry->joinWithAND(high, dry); 120 | FuzzyRuleConsequent *thenLow3 = new FuzzyRuleConsequent(); 121 | thenLow3->addOutput(lowHumidity); 122 | FuzzyRule *fuzzyRule9 = new FuzzyRule(9, ifHighAndDry, thenLow3); 123 | fuzzy->addFuzzyRule(fuzzyRule9); 124 | 125 | // Building FuzzyRule 126 | FuzzyRuleAntecedent *ifHighAndComfortable = new FuzzyRuleAntecedent(); 127 | ifHighAndComfortable->joinWithAND(high, comfortable); 128 | FuzzyRuleConsequent *thenMedium2 = new FuzzyRuleConsequent(); 129 | thenMedium2->addOutput(medium); 130 | FuzzyRule *fuzzyRule10 = new FuzzyRule(10, ifHighAndComfortable, thenMedium2); 131 | fuzzy->addFuzzyRule(fuzzyRule10); 132 | 133 | // Building FuzzyRule 134 | FuzzyRuleAntecedent *ifHighAndHumid = new FuzzyRuleAntecedent(); 135 | ifHighAndHumid->joinWithAND(high, humid); 136 | FuzzyRuleConsequent *thenFast1 = new FuzzyRuleConsequent(); 137 | thenFast1->addOutput(fast); 138 | FuzzyRule *fuzzyRule11 = new FuzzyRule(11, ifHighAndHumid, thenFast1); 139 | fuzzy->addFuzzyRule(fuzzyRule11); 140 | 141 | // Building FuzzyRule 142 | FuzzyRuleAntecedent *ifHighAndSticky = new FuzzyRuleAntecedent(); 143 | ifHighAndSticky->joinWithAND(high, sticky); 144 | FuzzyRuleConsequent *thenFast2 = new FuzzyRuleConsequent(); 145 | thenFast2->addOutput(fast); 146 | FuzzyRule *fuzzyRule12 = new FuzzyRule(12, ifHighAndSticky, thenFast2); 147 | fuzzy->addFuzzyRule(fuzzyRule12); 148 | 149 | // Building FuzzyRule 150 | FuzzyRuleAntecedent *ifVeryHighAndDry = new FuzzyRuleAntecedent(); 151 | ifVeryHighAndDry->joinWithAND(veryHigh, dry); 152 | FuzzyRuleConsequent *thenMedium3 = new FuzzyRuleConsequent(); 153 | thenMedium3->addOutput(medium); 154 | FuzzyRule *fuzzyRule13 = new FuzzyRule(13, ifVeryHighAndDry, thenMedium3); 155 | fuzzy->addFuzzyRule(fuzzyRule13); 156 | 157 | // Building FuzzyRule 158 | FuzzyRuleAntecedent *ifVeryHighAndComfortable = new FuzzyRuleAntecedent(); 159 | ifVeryHighAndComfortable->joinWithAND(veryHigh, comfortable); 160 | FuzzyRuleConsequent *thenFast3 = new FuzzyRuleConsequent(); 161 | thenFast3->addOutput(fast); 162 | FuzzyRule *fuzzyRule14 = new FuzzyRule(14, ifVeryHighAndComfortable, thenFast3); 163 | fuzzy->addFuzzyRule(fuzzyRule14); 164 | 165 | // Building FuzzyRule 166 | FuzzyRuleAntecedent *ifVeryHighAndHumid = new FuzzyRuleAntecedent(); 167 | ifVeryHighAndHumid->joinWithAND(veryHigh, humid); 168 | FuzzyRuleConsequent *thenFast4 = new FuzzyRuleConsequent(); 169 | thenFast4->addOutput(fast); 170 | FuzzyRule *fuzzyRule15 = new FuzzyRule(15, ifVeryHighAndHumid, thenFast4); 171 | fuzzy->addFuzzyRule(fuzzyRule15); 172 | 173 | // Building FuzzyRule 174 | FuzzyRuleAntecedent *ifVeryHighAndSticky = new FuzzyRuleAntecedent(); 175 | ifVeryHighAndSticky->joinWithAND(veryHigh, sticky); 176 | FuzzyRuleConsequent *thenFast5 = new FuzzyRuleConsequent(); 177 | thenFast5->addOutput(fast); 178 | FuzzyRule *fuzzyRule16 = new FuzzyRule(16, ifVeryHighAndSticky, thenFast5); 179 | fuzzy->addFuzzyRule(fuzzyRule16); 180 | 181 | // run it 182 | ofstream outputFile; 183 | outputFile.open("tests/output.txt"); 184 | 185 | for (int t = 0; t <= 45; t++) 186 | { 187 | for (int h = 0; h <= 100; h++) 188 | { 189 | fuzzy->setInput(1, t); 190 | fuzzy->setInput(2, h); 191 | 192 | fuzzy->fuzzify(); 193 | 194 | float o = fuzzy->defuzzify(1); 195 | 196 | std::cout 197 | << "Running with: Temperature->" << t << ", Humidity->" << h << ". Result: " << o << std::endl; 198 | 199 | outputFile << o << ","; 200 | } 201 | outputFile << "\n"; 202 | } 203 | outputFile.close(); 204 | return 0; 205 | } -------------------------------------------------------------------------------- /Fuzzy.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | * Robotic Research Group (RRG) 3 | * State University of Piauí (UESPI), Brazil - Piauí - Teresina 4 | * 5 | * Fuzzy.cpp 6 | * 7 | * Author: AJ Alves 8 | * Co authors: Dr. Ricardo Lira 9 | * Msc. Marvin Lemos 10 | * Douglas S. Kridi 11 | * Kannya Leal 12 | */ 13 | #include "Fuzzy.h" 14 | 15 | // CONTRUCTORS 16 | Fuzzy::Fuzzy() 17 | { 18 | // Initializing pointers with NULL 19 | // FuzzyInput 20 | this->fuzzyInputs = NULL; 21 | // FuzzyOutput 22 | this->fuzzyOutputs = NULL; 23 | // FuzzyRule 24 | this->fuzzyRules = NULL; 25 | } 26 | 27 | // DESTRUCTOR 28 | Fuzzy::~Fuzzy() 29 | { 30 | this->cleanFuzzyInputs(this->fuzzyInputs); 31 | this->cleanFuzzyOutputs(this->fuzzyOutputs); 32 | this->cleanFuzzyRules(this->fuzzyRules); 33 | } 34 | 35 | // PUBLIC METHODS 36 | 37 | // Method to include a new FuzzyInput into Fuzzy 38 | bool Fuzzy::addFuzzyInput(FuzzyInput *fuzzyInput) 39 | { 40 | // auxiliary variable to handle the operation 41 | fuzzyInputArray *newOne; 42 | // allocating in memory 43 | if ((newOne = (fuzzyInputArray *)malloc(sizeof(fuzzyInputArray))) == NULL) 44 | { 45 | // return false if in out of memory 46 | return false; 47 | } 48 | // building the object 49 | newOne->fuzzyInput = fuzzyInput; 50 | newOne->next = NULL; 51 | // if it is the first FuzzyInput, set it as the head 52 | if (this->fuzzyInputs == NULL) 53 | { 54 | this->fuzzyInputs = newOne; 55 | } 56 | else 57 | { 58 | // auxiliary variable to handle the operation 59 | fuzzyInputArray *aux = this->fuzzyInputs; 60 | // find the last element of the array 61 | while (aux != NULL) 62 | { 63 | if (aux->next == NULL) 64 | { 65 | // make the ralations between them 66 | aux->next = newOne; 67 | return true; 68 | } 69 | aux = aux->next; 70 | } 71 | } 72 | return true; 73 | } 74 | 75 | // Method to include a new FuzzyOutput into Fuzzy 76 | bool Fuzzy::addFuzzyOutput(FuzzyOutput *fuzzyOutput) 77 | { 78 | // auxiliary variable to handle the operation 79 | fuzzyOutputArray *newOne; 80 | // allocating in memory 81 | if ((newOne = (fuzzyOutputArray *)malloc(sizeof(fuzzyOutputArray))) == NULL) 82 | { 83 | // return false if in out of memory 84 | return false; 85 | } 86 | // building the object 87 | newOne->fuzzyOutput = fuzzyOutput; 88 | newOne->next = NULL; 89 | // sorting the fuzzyOutput 90 | fuzzyOutput->order(); 91 | // if it is the first FuzzyOutput, set it as the head 92 | if (this->fuzzyOutputs == NULL) 93 | { 94 | this->fuzzyOutputs = newOne; 95 | } 96 | else 97 | { 98 | // auxiliary variable to handle the operation 99 | fuzzyOutputArray *aux = this->fuzzyOutputs; 100 | // find the last element of the array 101 | while (aux != NULL) 102 | { 103 | if (aux->next == NULL) 104 | { 105 | // make the ralations between them 106 | aux->next = newOne; 107 | return true; 108 | } 109 | aux = aux->next; 110 | } 111 | } 112 | return true; 113 | } 114 | 115 | // Method to include a new FuzzyRule into Fuzzy 116 | bool Fuzzy::addFuzzyRule(FuzzyRule *fuzzyRule) 117 | { 118 | // auxiliary variable to handle the operation 119 | fuzzyRuleArray *newOne; 120 | // allocating in memory 121 | if ((newOne = (fuzzyRuleArray *)malloc(sizeof(fuzzyRuleArray))) == NULL) 122 | { 123 | // return false if in out of memory 124 | return false; 125 | } 126 | // building the object 127 | newOne->fuzzyRule = fuzzyRule; 128 | newOne->next = NULL; 129 | // if it is the first FuzzyOutput, set it as the head 130 | if (this->fuzzyRules == NULL) 131 | { 132 | this->fuzzyRules = newOne; 133 | } 134 | else 135 | { 136 | // auxiliary variable to handle the operation 137 | fuzzyRuleArray *aux = this->fuzzyRules; 138 | // find the last element of the array 139 | while (aux != NULL) 140 | { 141 | if (aux->next == NULL) 142 | { 143 | // make the ralations between them 144 | aux->next = newOne; 145 | return true; 146 | } 147 | aux = aux->next; 148 | } 149 | } 150 | return true; 151 | } 152 | 153 | // Method to set a crisp value to one FuzzyInput 154 | bool Fuzzy::setInput(int fuzzyInputIndex, float crispValue) 155 | { 156 | // auxiliary variable to handle the operation 157 | fuzzyInputArray *aux; 158 | // instantiate with the first element from array 159 | aux = this->fuzzyInputs; 160 | // while not in the end of the array, iterate 161 | while (aux != NULL) 162 | { 163 | // if the FuzzyInput index match with the desired 164 | if (aux->fuzzyInput->getIndex() == fuzzyInputIndex) 165 | { 166 | // set crisp value for this FuzzyInput and return true 167 | aux->fuzzyInput->setCrispInput(crispValue); 168 | return true; 169 | } 170 | aux = aux->next; 171 | } 172 | // if no FuzzyInput was found, return false 173 | return false; 174 | } 175 | 176 | // Method to start the calculate of the result 177 | bool Fuzzy::fuzzify() 178 | { 179 | // auxiliary variable to handle the operation 180 | fuzzyInputArray *fuzzyInputAux; 181 | fuzzyOutputArray *fuzzyOutputAux; 182 | fuzzyRuleArray *fuzzyRuleAux; 183 | // to reset the data of all FuzzyInput and FuzzyOutput objects 184 | // instantiate with first element of the array 185 | fuzzyInputAux = this->fuzzyInputs; 186 | // while not in the end of the array, iterate 187 | while (fuzzyInputAux != NULL) 188 | { 189 | // for each FuzzyInput, reset its data 190 | fuzzyInputAux->fuzzyInput->resetFuzzySets(); 191 | fuzzyInputAux = fuzzyInputAux->next; 192 | } 193 | // instantiate with first element of the array 194 | fuzzyOutputAux = this->fuzzyOutputs; 195 | // while not in the end of the array, iterate 196 | while (fuzzyOutputAux != NULL) 197 | { 198 | // for each FuzzyOutput, reset its data 199 | fuzzyOutputAux->fuzzyOutput->resetFuzzySets(); 200 | fuzzyOutputAux = fuzzyOutputAux->next; 201 | } 202 | // to calculate the pertinence of all FuzzyInput objects 203 | // instantiate with first element of the array 204 | fuzzyInputAux = this->fuzzyInputs; 205 | // while not in the end of the array, iterate 206 | while (fuzzyInputAux != NULL) 207 | { 208 | // for each FuzzyInput, calculate its pertinence 209 | fuzzyInputAux->fuzzyInput->calculateFuzzySetPertinences(); 210 | fuzzyInputAux = fuzzyInputAux->next; 211 | } 212 | // to evaluate which rules were triggered 213 | // instantiate with first element of the array 214 | fuzzyRuleAux = this->fuzzyRules; 215 | // while not in the end of the array, iterate 216 | while (fuzzyRuleAux != NULL) 217 | { 218 | // for each FuzzyRule, evaluate its expressions 219 | fuzzyRuleAux->fuzzyRule->evaluateExpression(); 220 | fuzzyRuleAux = fuzzyRuleAux->next; 221 | } 222 | // to truncate the output sets 223 | // instantiate with first element of the array 224 | fuzzyOutputAux = this->fuzzyOutputs; 225 | // while not in the end of the array, iterate 226 | while (fuzzyOutputAux != NULL) 227 | { 228 | // for each FuzzyOutput, truncate the result 229 | fuzzyOutputAux->fuzzyOutput->truncate(); 230 | fuzzyOutputAux = fuzzyOutputAux->next; 231 | } 232 | return true; 233 | } 234 | 235 | // Method to verify if one specific FuzzyRule was triggered 236 | bool Fuzzy::isFiredRule(int fuzzyRuleIndex) 237 | { 238 | // auxiliary variable to handle the operation 239 | fuzzyRuleArray *aux; 240 | // instantiate with first element of the array 241 | aux = this->fuzzyRules; 242 | // while not in the end of the array, iterate 243 | while (aux != NULL) 244 | { 245 | // if the FuzzyRule index match with the desired 246 | if (aux->fuzzyRule->getIndex() == fuzzyRuleIndex) 247 | { 248 | // return the calculated result 249 | return aux->fuzzyRule->isFired(); 250 | } 251 | aux = aux->next; 252 | } 253 | // if no FuzzyRule was found, return false 254 | return false; 255 | } 256 | 257 | // Method to retrieve the result of the process for one specific FuzzyOutput 258 | float Fuzzy::defuzzify(int fuzzyOutputIndex) 259 | { 260 | // auxiliary variable to handle the operation 261 | fuzzyOutputArray *aux; 262 | // instantiate with first element of the array 263 | aux = this->fuzzyOutputs; 264 | // while not in the end of the array, iterate 265 | while (aux != NULL) 266 | { 267 | // if the FuzzyOutput index match with the desired 268 | if (aux->fuzzyOutput->getIndex() == fuzzyOutputIndex) 269 | { 270 | // return the calculated result 271 | return aux->fuzzyOutput->getCrispOutput(); 272 | } 273 | aux = aux->next; 274 | } 275 | return 0; 276 | } 277 | 278 | // PRIVATE METHODS 279 | 280 | // Method to recursively clean all FuzzyInput from memory 281 | void Fuzzy::cleanFuzzyInputs(fuzzyInputArray *aux) 282 | { 283 | if (aux != NULL) 284 | { 285 | this->cleanFuzzyInputs(aux->next); 286 | // emptying allocated memory 287 | free(aux); 288 | } 289 | } 290 | 291 | // Method to recursively clean all FuzzyOutput from memory 292 | void Fuzzy::cleanFuzzyOutputs(fuzzyOutputArray *aux) 293 | { 294 | if (aux != NULL) 295 | { 296 | this->cleanFuzzyOutputs(aux->next); 297 | // emptying allocated memory 298 | free(aux); 299 | } 300 | } 301 | 302 | // Method to recursively clean all FuzzyRule from memory 303 | void Fuzzy::cleanFuzzyRules(fuzzyRuleArray *aux) 304 | { 305 | if (aux != NULL) 306 | { 307 | this->cleanFuzzyRules(aux->next); 308 | // emptying allocated memory 309 | free(aux); 310 | } 311 | } -------------------------------------------------------------------------------- /FuzzyRuleAntecedent.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | * Robotic Research Group (RRG) 3 | * State University of Piauí (UESPI), Brazil - Piauí - Teresina 4 | * 5 | * FuzzyRuleAntecedent.cpp 6 | * 7 | * Author: AJ Alves 8 | * Co authors: Dr. Ricardo Lira 9 | * Msc. Marvin Lemos 10 | * Douglas S. Kridi 11 | * Kannya Leal 12 | */ 13 | #include "FuzzyRuleAntecedent.h" 14 | 15 | // CONTRUCTORS 16 | FuzzyRuleAntecedent::FuzzyRuleAntecedent() 17 | { 18 | // set the initial values 19 | this->op = 0; 20 | this->mode = 0; 21 | this->fuzzySet1 = NULL; 22 | this->fuzzySet2 = NULL; 23 | this->fuzzyRuleAntecedent1 = NULL; 24 | this->fuzzyRuleAntecedent2 = NULL; 25 | } 26 | 27 | // PUBLIC METHODS 28 | 29 | // Method to create a FuzzyRuleAntecedent with just one single FuzzySet 30 | bool FuzzyRuleAntecedent::joinSingle(FuzzySet *fuzzySet) 31 | { 32 | // check if FuzzySet is not null 33 | if (fuzzySet != NULL) 34 | { 35 | // set the mode and reference 36 | this->mode = MODE_FS; 37 | this->fuzzySet1 = fuzzySet; 38 | return true; 39 | } 40 | return false; 41 | } 42 | 43 | // Method to create a FuzzyRuleAntecedent with two FuzzySet, with AND 44 | bool FuzzyRuleAntecedent::joinWithAND(FuzzySet *fuzzySet1, FuzzySet *fuzzySet2) 45 | { 46 | // check if two FuzzySet are valid 47 | if (fuzzySet1 != NULL && fuzzySet2 != NULL) 48 | { 49 | // set the mode and references 50 | this->op = OP_AND; 51 | this->mode = MODE_FS_FS; 52 | this->fuzzySet1 = fuzzySet1; 53 | this->fuzzySet2 = fuzzySet2; 54 | return true; 55 | } 56 | return false; 57 | } 58 | 59 | // Method to create a FuzzyRuleAntecedent with two FuzzySet, with OR 60 | bool FuzzyRuleAntecedent::joinWithOR(FuzzySet *fuzzySet1, FuzzySet *fuzzySet2) 61 | { 62 | // check if two FuzzySet are valid 63 | if (fuzzySet1 != NULL && fuzzySet2 != NULL) 64 | { 65 | // set the mode and references 66 | this->op = OP_OR; 67 | this->mode = MODE_FS_FS; 68 | this->fuzzySet1 = fuzzySet1; 69 | this->fuzzySet2 = fuzzySet2; 70 | return true; 71 | } 72 | return false; 73 | } 74 | 75 | // Method to create a FuzzyRuleAntecedent with one FuzzySet and one FuzzyRuleAntecedent, with AND 76 | bool FuzzyRuleAntecedent::joinWithAND(FuzzySet *fuzzySet, FuzzyRuleAntecedent *fuzzyRuleAntecedent) 77 | { 78 | // check if the FuzzySet and FuzzyRuleAntecedent are valid 79 | if (fuzzySet != NULL && fuzzyRuleAntecedent != NULL) 80 | { 81 | // set the mode and references 82 | this->op = OP_AND; 83 | this->mode = MODE_FS_FRA; 84 | this->fuzzySet1 = fuzzySet; 85 | this->fuzzyRuleAntecedent1 = fuzzyRuleAntecedent; 86 | return true; 87 | } 88 | return false; 89 | } 90 | 91 | // Method to create a FuzzyRuleAntecedent with one FuzzySet and one FuzzyRuleAntecedent, with AND (Inverse Params) 92 | bool FuzzyRuleAntecedent::joinWithAND(FuzzyRuleAntecedent *fuzzyRuleAntecedent, FuzzySet *fuzzySet) 93 | { 94 | return this->joinWithAND(fuzzySet, fuzzyRuleAntecedent); 95 | } 96 | 97 | // Method to create a FuzzyRuleAntecedent with one FuzzySet and one FuzzyRuleAntecedent, with OR 98 | bool FuzzyRuleAntecedent::joinWithOR(FuzzySet *fuzzySet, FuzzyRuleAntecedent *fuzzyRuleAntecedent) 99 | { 100 | // check if the FuzzySet and FuzzyRuleAntecedent are valid 101 | if (fuzzySet != NULL && fuzzyRuleAntecedent != NULL) 102 | { 103 | // set the mode and references 104 | this->op = OP_OR; 105 | this->mode = MODE_FS_FRA; 106 | this->fuzzySet1 = fuzzySet; 107 | this->fuzzyRuleAntecedent1 = fuzzyRuleAntecedent; 108 | return true; 109 | } 110 | return false; 111 | } 112 | 113 | // Method to create a FuzzyRuleAntecedent with one FuzzySet and one FuzzyRuleAntecedent, with OR (Inverse Params) 114 | bool FuzzyRuleAntecedent::joinWithOR(FuzzyRuleAntecedent *fuzzyRuleAntecedent, FuzzySet *fuzzySet) 115 | { 116 | return this->joinWithOR(fuzzySet, fuzzyRuleAntecedent); 117 | } 118 | 119 | // Method to create a FuzzyRuleAntecedent with two FuzzyRuleAntecedent, with AND 120 | bool FuzzyRuleAntecedent::joinWithAND(FuzzyRuleAntecedent *fuzzyRuleAntecedent1, FuzzyRuleAntecedent *fuzzyRuleAntecedent2) 121 | { 122 | // check if two FuzzyRuleAntecedent are valid 123 | if (fuzzyRuleAntecedent1 != NULL && fuzzyRuleAntecedent2 != NULL) 124 | { 125 | // set the mode and references 126 | this->op = OP_AND; 127 | this->mode = MODE_FRA_FRA; 128 | this->fuzzyRuleAntecedent1 = fuzzyRuleAntecedent1; 129 | this->fuzzyRuleAntecedent2 = fuzzyRuleAntecedent2; 130 | return true; 131 | } 132 | return false; 133 | } 134 | 135 | // Method to create a FuzzyRuleAntecedent with two FuzzyRuleAntecedent, with OR 136 | bool FuzzyRuleAntecedent::joinWithOR(FuzzyRuleAntecedent *fuzzyRuleAntecedent1, FuzzyRuleAntecedent *fuzzyRuleAntecedent2) 137 | { 138 | // check if two FuzzyRuleAntecedent are valid 139 | if (fuzzyRuleAntecedent1 != NULL && fuzzyRuleAntecedent2 != NULL) 140 | { 141 | // set the mode and references 142 | this->op = OP_OR; 143 | this->mode = MODE_FRA_FRA; 144 | this->fuzzyRuleAntecedent1 = fuzzyRuleAntecedent1; 145 | this->fuzzyRuleAntecedent2 = fuzzyRuleAntecedent2; 146 | return true; 147 | } 148 | return false; 149 | } 150 | 151 | // Method to evaluate this FuzzyRuleAntecedent 152 | float FuzzyRuleAntecedent::evaluate() 153 | { 154 | // switch by the mode value 155 | switch (this->mode) 156 | { 157 | case MODE_FS: 158 | // case it is a single FuzzySet join, just return its pertinence 159 | return this->fuzzySet1->getPertinence(); 160 | break; 161 | case MODE_FS_FS: 162 | // case it is a join of two FuzzySet, switch by the operator 163 | switch (this->op) 164 | { 165 | case OP_AND: 166 | // case the operator is AND, check if both has pertinence bigger then 0.0 167 | if (this->fuzzySet1->getPertinence() > 0.0 && this->fuzzySet2->getPertinence() > 0.0) 168 | { 169 | // in this case, return the small pertinence between two FuzzySet 170 | if (this->fuzzySet1->getPertinence() < this->fuzzySet2->getPertinence()) 171 | { 172 | return this->fuzzySet1->getPertinence(); 173 | } 174 | else 175 | { 176 | return this->fuzzySet2->getPertinence(); 177 | } 178 | } 179 | else 180 | { 181 | return 0.0; 182 | } 183 | break; 184 | case OP_OR: 185 | // case the operator is OR, check if one has pertinence bigger then 0.0 186 | if (this->fuzzySet1->getPertinence() > 0.0 || this->fuzzySet2->getPertinence() > 0.0) 187 | { 188 | // in this case, return the one pertinence is bigger 189 | if (this->fuzzySet1->getPertinence() > this->fuzzySet2->getPertinence()) 190 | { 191 | return this->fuzzySet1->getPertinence(); 192 | } 193 | else 194 | { 195 | return this->fuzzySet2->getPertinence(); 196 | } 197 | } 198 | else 199 | { 200 | return 0.0; 201 | } 202 | break; 203 | } 204 | break; 205 | case MODE_FS_FRA: 206 | // case it is a join of one FuzzySet and one FuzzyRuleAntecedent, switch by the operator 207 | switch (this->op) 208 | { 209 | case OP_AND: 210 | // case the operator is AND, check if both has pertinence bigger then 0.0 211 | if (this->fuzzySet1->getPertinence() > 0.0 && fuzzyRuleAntecedent1->evaluate() > 0.0) 212 | { 213 | // in this case, return the small pertinence between two FuzzySet 214 | if (this->fuzzySet1->getPertinence() < fuzzyRuleAntecedent1->evaluate()) 215 | { 216 | return this->fuzzySet1->getPertinence(); 217 | } 218 | else 219 | { 220 | return fuzzyRuleAntecedent1->evaluate(); 221 | } 222 | } 223 | else 224 | { 225 | return 0.0; 226 | } 227 | break; 228 | case OP_OR: 229 | // case the operator is OR, check if one has pertinence bigger then 0.0 230 | if (this->fuzzySet1->getPertinence() > 0.0 || fuzzyRuleAntecedent1->evaluate() > 0.0) 231 | { 232 | // in this case, return the one pertinence is bigger 233 | if (this->fuzzySet1->getPertinence() > fuzzyRuleAntecedent1->evaluate()) 234 | { 235 | return this->fuzzySet1->getPertinence(); 236 | } 237 | else 238 | { 239 | return fuzzyRuleAntecedent1->evaluate(); 240 | } 241 | } 242 | else 243 | { 244 | return 0.0; 245 | } 246 | break; 247 | } 248 | break; 249 | case MODE_FRA_FRA: 250 | // case it is a join of two FuzzyRuleAntecedent, switch by the operator 251 | switch (this->op) 252 | { 253 | case OP_AND: 254 | // case the operator is AND, check if both has pertinence bigger then 0.0 255 | if (fuzzyRuleAntecedent1->evaluate() > 0.0 && fuzzyRuleAntecedent2->evaluate() > 0.0) 256 | { 257 | // in this case, return the small pertinence between two FuzzySet 258 | if (fuzzyRuleAntecedent1->evaluate() < fuzzyRuleAntecedent2->evaluate()) 259 | { 260 | return fuzzyRuleAntecedent1->evaluate(); 261 | } 262 | else 263 | { 264 | return fuzzyRuleAntecedent2->evaluate(); 265 | } 266 | } 267 | else 268 | { 269 | return 0.0; 270 | } 271 | break; 272 | case OP_OR: 273 | // case the operator is OR, check if one has pertinence bigger then 0.0 274 | if (fuzzyRuleAntecedent1->evaluate() > 0.0 || fuzzyRuleAntecedent2->evaluate() > 0.0) 275 | { 276 | // in this case, return the one pertinence is bigger 277 | if (fuzzyRuleAntecedent1->evaluate() > fuzzyRuleAntecedent2->evaluate()) 278 | { 279 | return fuzzyRuleAntecedent1->evaluate(); 280 | } 281 | else 282 | { 283 | return fuzzyRuleAntecedent2->evaluate(); 284 | } 285 | } 286 | else 287 | { 288 | return 0.0; 289 | } 290 | break; 291 | } 292 | break; 293 | } 294 | return 0.0; 295 | } -------------------------------------------------------------------------------- /FuzzyComposition.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | * Robotic Research Group (RRG) 3 | * State University of Piauí (UESPI), Brazil - Piauí - Teresina 4 | * 5 | * FuzzyComposition.cpp 6 | * 7 | * Author: AJ Alves 8 | * Co authors: Dr. Ricardo Lira 9 | * Msc. Marvin Lemos 10 | * Douglas S. Kridi 11 | * Kannya Leal 12 | */ 13 | #include "FuzzyComposition.h" 14 | #include 15 | 16 | // CONTRUCTORS 17 | FuzzyComposition::FuzzyComposition() 18 | { 19 | this->points = NULL; 20 | } 21 | 22 | // DESTRUCTOR 23 | FuzzyComposition::~FuzzyComposition() 24 | { 25 | this->cleanPoints(this->points); 26 | } 27 | 28 | // Method to include a new pointsArray struct into FuzzyComposition 29 | bool FuzzyComposition::addPoint(float point, float pertinence) 30 | { 31 | // auxiliary variable to handle the operation 32 | pointsArray *newOne; 33 | // allocating in memory 34 | if ((newOne = (pointsArray *)malloc(sizeof(pointsArray))) == NULL) 35 | { 36 | // return false if in out of memory 37 | return false; 38 | } 39 | // populate the struct 40 | newOne->previous = NULL; 41 | newOne->point = point; 42 | newOne->pertinence = pertinence; 43 | newOne->next = NULL; 44 | // if it is the first pointsArray, set it as the head 45 | if (this->points == NULL) 46 | { 47 | this->points = newOne; 48 | } 49 | else 50 | { 51 | // auxiliary variable to handle the operation 52 | pointsArray *aux = this->points; 53 | // find the last element of the array 54 | while (aux != NULL) 55 | { 56 | if (aux->next == NULL) 57 | { 58 | // make the relations between them 59 | newOne->previous = aux; 60 | aux->next = newOne; 61 | return true; 62 | } 63 | aux = aux->next; 64 | } 65 | } 66 | return true; 67 | } 68 | 69 | // Method to check if FuzzyComposition contains an specific point and pertinence 70 | bool FuzzyComposition::checkPoint(float point, float pertinence) 71 | { 72 | // auxiliary variable to handle the operation 73 | pointsArray *aux = this->points; 74 | // while not in the end of the array, iterate 75 | while (aux != NULL) 76 | { 77 | // if params match with this point 78 | if (aux->point == point && aux->pertinence == pertinence) 79 | { 80 | return true; 81 | } 82 | aux = aux->next; 83 | } 84 | return false; 85 | } 86 | 87 | // Method to iterate over the pointsArray, detect possible intersections and sent these points for "correction" 88 | bool FuzzyComposition::build() 89 | { 90 | // auxiliary variable to handle the operation, instantiate with the first element from array 91 | pointsArray *aux = this->points; 92 | // while not in the end of the array, iterate 93 | while (aux != NULL) 94 | { 95 | // another auxiliary variable to handle the operation 96 | pointsArray *temp = aux; 97 | // while not in the beginning of the array, iterate 98 | while (temp->previous != NULL) 99 | { 100 | // if the previous point is greater then the current 101 | if (aux->point < temp->point) 102 | { 103 | // if yes, break an use this point 104 | break; 105 | } 106 | temp = temp->previous; 107 | } 108 | // iterate over the previous pointsArray 109 | while (temp->previous != NULL) 110 | { 111 | // if previous of previous point is not NULL, and some intersection was fixed by rebuild 112 | if (this->rebuild(aux, aux->next, temp, temp->previous) == true) 113 | { 114 | // move the first auxiliary to beginning of the array for a new validation, and breaks 115 | aux = this->points; 116 | break; 117 | } 118 | temp = temp->previous; 119 | } 120 | aux = aux->next; 121 | } 122 | return true; 123 | } 124 | 125 | // Method to calculate the center of the area of this FuzzyComposition 126 | float FuzzyComposition::calculate() 127 | { 128 | // auxiliary variable to handle the operation, instantiate with the first element from array 129 | pointsArray *aux = this->points; 130 | float numerator = 0.0; 131 | float denominator = 0.0; 132 | // while not in the end of the array, iterate 133 | while (aux != NULL && aux->next != NULL) 134 | { 135 | float area = 0.0; 136 | float middle = 0.0; 137 | // if it is a singleton 138 | if (aux->pertinence != aux->next->pertinence && aux->point == aux->next->point) 139 | { 140 | // enter in all points of singleton, but calculate only once 141 | if (aux->pertinence > 0.0) 142 | { 143 | area = aux->pertinence; 144 | middle = aux->point; 145 | } 146 | } 147 | // if a triangle (Not properly a membership function) 148 | else if (aux->pertinence == 0.0 || aux->next->pertinence == 0.0) 149 | { 150 | float pertinence; 151 | if (aux->pertinence > 0.0) 152 | { 153 | pertinence = aux->pertinence; 154 | } 155 | else 156 | { 157 | pertinence = aux->next->pertinence; 158 | } 159 | area = ((aux->next->point - aux->point) * pertinence) / 2.0; 160 | if (aux->pertinence < aux->next->pertinence) 161 | { 162 | middle = ((aux->next->point - aux->point) / 1.5) + aux->point; 163 | } 164 | else 165 | { 166 | middle = ((aux->next->point - aux->point) / 3.0) + aux->point; 167 | } 168 | } 169 | // else if a square (Not properly a membership function) 170 | else if ((aux->pertinence > 0.0 && aux->next->pertinence > 0.0) && aux->pertinence == aux->next->pertinence) 171 | { 172 | area = (aux->next->point - aux->point) * aux->pertinence; 173 | middle = ((aux->next->point - aux->point) / 2.0) + aux->point; 174 | } 175 | // else if a trapeze (Not properly a membership function) 176 | else if ((aux->pertinence > 0.0 && aux->next->pertinence > 0.0) && aux->pertinence != aux->next->pertinence) 177 | { 178 | area = ((aux->pertinence + aux->next->pertinence) / 2.0) * (aux->next->point - aux->point); 179 | middle = ((aux->next->point - aux->point) / 2.0) + aux->point; 180 | } 181 | numerator += middle * area; 182 | denominator += area; 183 | aux = aux->next; 184 | } 185 | // avoiding zero division 186 | if (denominator == 0.0) 187 | { 188 | return 0.0; 189 | } 190 | else 191 | { 192 | return numerator / denominator; 193 | } 194 | } 195 | 196 | // Method to reset the Object 197 | bool FuzzyComposition::empty() 198 | { 199 | // clean all pointsArray from memory 200 | this->cleanPoints(this->points); 201 | // reset the pointer 202 | this->points = NULL; 203 | return true; 204 | } 205 | 206 | // Method to count the amount of points used in this FuzzyComposition 207 | int FuzzyComposition::countPoints() 208 | { 209 | // variable to hold the count 210 | int count = 0; 211 | // auxiliary variable to handle the operation 212 | pointsArray *aux = this->points; 213 | // while not in the end of the array, iterate 214 | while (aux != NULL) 215 | { 216 | count = count + 1; 217 | aux = aux->next; 218 | } 219 | return count; 220 | } 221 | 222 | // PRIVATE METHODS 223 | 224 | // Method to recursively clean all pointsArray structs from memory 225 | void FuzzyComposition::cleanPoints(pointsArray *aux) 226 | { 227 | if (aux != NULL) 228 | { 229 | this->cleanPoints(aux->next); 230 | // emptying allocated memory 231 | free(aux); 232 | } 233 | } 234 | 235 | // Method to search intersection between two segments, if found, create a new pointsArray (in found intersection) and remove not necessary ones 236 | bool FuzzyComposition::rebuild(pointsArray *aSegmentBegin, pointsArray *aSegmentEnd, pointsArray *bSegmentBegin, pointsArray *bSegmentEnd) 237 | { 238 | // create a reference for each point 239 | float x1 = aSegmentBegin->point; 240 | float y1 = aSegmentBegin->pertinence; 241 | float x2 = aSegmentEnd->point; 242 | float y2 = aSegmentEnd->pertinence; 243 | float x3 = bSegmentBegin->point; 244 | float y3 = bSegmentBegin->pertinence; 245 | float x4 = bSegmentEnd->point; 246 | float y4 = bSegmentEnd->pertinence; 247 | // calculate the denominator and numerator 248 | float denom = (y4 - y3) * (x2 - x1) - (x4 - x3) * (y2 - y1); 249 | float numera = (x4 - x3) * (y1 - y3) - (y4 - y3) * (x1 - x3); 250 | float numerb = (x2 - x1) * (y1 - y3) - (y2 - y1) * (x1 - x3); 251 | // if negative, convert to positive 252 | if (denom < 0.0) 253 | { 254 | denom *= -1.0; 255 | } 256 | // If the denominator is zero or close to it, it means that the lines are parallels, so return false for intersection 257 | if (denom < EPSILON_VALUE) 258 | { 259 | // return false for intersection 260 | return false; 261 | } 262 | // if negative, convert to positive 263 | if (numera < 0.0) 264 | { 265 | numera *= -1.0; 266 | } 267 | // if negative, convert to positive 268 | if (numerb < 0.0) 269 | { 270 | numerb *= -1.0; 271 | } 272 | // verify if has intersection between the segments 273 | float mua = numera / denom; 274 | float mub = numerb / denom; 275 | if (mua <= 0.0 || mua >= 1.0 || mub <= 0.0 || mub >= 1.0) 276 | { 277 | // return false for intersection 278 | return false; 279 | } 280 | else 281 | { 282 | // we found an intersection 283 | // auxiliary variable to handle the operation 284 | pointsArray *aux; 285 | // allocating in memory 286 | if ((aux = (pointsArray *)malloc(sizeof(pointsArray))) == NULL) 287 | { 288 | // return false if in out of memory 289 | return false; 290 | } 291 | // calculate the point (y) and its pertinence (y) for the new element (pointsArray) 292 | aux->previous = bSegmentEnd; 293 | aux->point = x1 + mua * (x2 - x1); 294 | aux->pertinence = y1 + mua * (y2 - y1); 295 | aux->next = aSegmentEnd; 296 | // changing pointsArray to accomplish with new state 297 | aSegmentBegin->next = aux; 298 | aSegmentEnd->previous = aux; 299 | bSegmentBegin->previous = aux; 300 | bSegmentEnd->next = aux; 301 | // initiate a proccess of remotion of not needed pointsArray 302 | // some variables to help in this proccess, the start pointsArray 303 | pointsArray *temp = bSegmentBegin; 304 | // do, while 305 | do 306 | { 307 | // hold next 308 | pointsArray *excl = temp->next; 309 | // remove it from array 310 | this->rmvPoint(temp); 311 | // set new current 312 | temp = excl; 313 | // check if it is the stop pointsArray 314 | if (temp != NULL && temp->point == aux->point && temp->pertinence == aux->pertinence) 315 | { 316 | // if true, stop the deletions 317 | break; 318 | } 319 | } while (temp != NULL); 320 | return true; 321 | } 322 | } 323 | 324 | // Function to remove (deallocate) some pointsArray 325 | bool FuzzyComposition::rmvPoint(pointsArray *point) 326 | { 327 | if (point != NULL) 328 | { 329 | // emptying allocated memory 330 | free(point); 331 | } 332 | return true; 333 | } -------------------------------------------------------------------------------- /FuzzyOutput.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | * Robotic Research Group (RRG) 3 | * State University of Piauí (UESPI), Brazil - Piauí - Teresina 4 | * 5 | * FuzzyOutput.cpp 6 | * 7 | * Author: AJ Alves 8 | * Co authors: Dr. Ricardo Lira 9 | * Msc. Marvin Lemos 10 | * Douglas S. Kridi 11 | * Kannya Leal 12 | */ 13 | #include "FuzzyOutput.h" 14 | 15 | // CONTRUCTORS 16 | FuzzyOutput::FuzzyOutput() : FuzzyIO() 17 | { 18 | // instantiating a FuzzyComposition object 19 | this->fuzzyComposition = new FuzzyComposition(); 20 | } 21 | 22 | FuzzyOutput::FuzzyOutput(int index) : FuzzyIO(index) 23 | { 24 | // instantiating a FuzzyComposition object 25 | this->fuzzyComposition = new FuzzyComposition(); 26 | } 27 | 28 | // DESTRUCTOR 29 | FuzzyOutput::~FuzzyOutput() 30 | { 31 | // reset fuzzyComposition object 32 | this->fuzzyComposition->empty(); 33 | } 34 | 35 | // PUBLIC METHODS 36 | 37 | bool FuzzyOutput::truncate() 38 | { 39 | // reset fuzzyComposition object 40 | this->fuzzyComposition->empty(); 41 | // auxiliary variable to handle the operation 42 | fuzzySetArray *aux = this->fuzzySets; 43 | // while not in the end of the array, iterate 44 | while (aux != NULL) 45 | { 46 | // if the FuzzySet was trigged (has some pertinence) 47 | if (aux->fuzzySet->getPertinence() > 0.0) 48 | { 49 | // Check if it is not a "trapeze" without its left triangle or singleton, before include the point A 50 | if (aux->fuzzySet->getPointA() != aux->fuzzySet->getPointB()) 51 | { 52 | // include it 53 | this->fuzzyComposition->addPoint(aux->fuzzySet->getPointA(), 0.0); 54 | } 55 | // check if it is a triangle (B == C) and (A <> D) 56 | if (aux->fuzzySet->getPointB() == aux->fuzzySet->getPointC() && aux->fuzzySet->getPointA() != aux->fuzzySet->getPointD()) 57 | { 58 | // check if the pertinence is the max 59 | if (aux->fuzzySet->getPertinence() == 1.0) 60 | { 61 | // include it (it will replace previous point if left triangle) 62 | this->fuzzyComposition->addPoint(aux->fuzzySet->getPointB(), aux->fuzzySet->getPertinence()); 63 | // include it (it will replace previous point if right triangle) 64 | this->fuzzyComposition->addPoint(aux->fuzzySet->getPointD(), 0.0); 65 | } 66 | // if the pertinence is below the max, and it is a triangle, calculate the new point B and C 67 | else 68 | { 69 | // rebuild the new point finding the intersection of two lines, the first is the segment from A to B (pertinence here is the y) and the segment of truncate, from A to D 70 | // initiate a new point with current values of B (here it does matters, it always will be changed) 71 | float newPointB = aux->fuzzySet->getPointB(); 72 | float newPertinenceB = aux->fuzzySet->getPertinence(); 73 | // only if a regular triangle 74 | this->rebuild(aux->fuzzySet->getPointA(), 0.0, aux->fuzzySet->getPointB(), 1.0, aux->fuzzySet->getPointA(), aux->fuzzySet->getPertinence(), aux->fuzzySet->getPointD(), aux->fuzzySet->getPertinence(), &newPointB, &newPertinenceB); 75 | // include it 76 | this->fuzzyComposition->addPoint(newPointB, newPertinenceB); 77 | // rebuild the new point finding the intersection of two lines, the second is the segment from C to D (pertinence here is the y) and the segment of truncate, from A to D 78 | // initiate a new point with current values of C (here it does matters, it always will be changed) 79 | float newPointC = aux->fuzzySet->getPointC(); 80 | float newPertinenceC = aux->fuzzySet->getPertinence(); 81 | // only if a regular triangle 82 | this->rebuild(aux->fuzzySet->getPointC(), 1.0, aux->fuzzySet->getPointD(), 0.0, aux->fuzzySet->getPointA(), aux->fuzzySet->getPertinence(), aux->fuzzySet->getPointD(), aux->fuzzySet->getPertinence(), &newPointC, &newPertinenceC); 83 | // include it 84 | this->fuzzyComposition->addPoint(newPointC, newPertinenceC); 85 | } 86 | } 87 | // if until now, it was not a triangle 88 | // check if (B <> C), if true, it is a trapeze (this code is the same of the triangle, except when the pertinence is 1.0, here we include the two points [B and C], because they are not equal) 89 | else if (aux->fuzzySet->getPointB() != aux->fuzzySet->getPointC()) 90 | { 91 | // check if the pertinence is the max 92 | if (aux->fuzzySet->getPertinence() == 1.0) 93 | { 94 | // include it 95 | this->fuzzyComposition->addPoint(aux->fuzzySet->getPointB(), aux->fuzzySet->getPertinence()); 96 | // include it 97 | this->fuzzyComposition->addPoint(aux->fuzzySet->getPointC(), aux->fuzzySet->getPertinence()); 98 | } 99 | // if the pertinence is below the max, and it is a triangle, calculate the new point B and C 100 | else 101 | { 102 | // initiate a new point with current values of B 103 | float newPointB = aux->fuzzySet->getPointB(); 104 | float newPertinenceB = aux->fuzzySet->getPertinence(); 105 | // rebuild the new point finding the intersection of two lines, the first is the segment from A to B (pertinence here is the y) and the segment of truncate, from A to D 106 | this->rebuild(aux->fuzzySet->getPointA(), 0.0, aux->fuzzySet->getPointB(), 1.0, aux->fuzzySet->getPointA(), aux->fuzzySet->getPertinence(), aux->fuzzySet->getPointD(), aux->fuzzySet->getPertinence(), &newPointB, &newPertinenceB); 107 | // include it 108 | this->fuzzyComposition->addPoint(newPointB, newPertinenceB); 109 | // initiate a new point with current values of C 110 | float newPointC = aux->fuzzySet->getPointC(); 111 | float newPertinenceC = aux->fuzzySet->getPertinence(); 112 | // rebuild the new point finding the intersection of two lines, the first is the segment from C to D (pertinence here is the y) and the segment of truncate, from A to D 113 | this->rebuild(aux->fuzzySet->getPointC(), 1.0, aux->fuzzySet->getPointD(), 0.0, aux->fuzzySet->getPointA(), aux->fuzzySet->getPertinence(), aux->fuzzySet->getPointD(), aux->fuzzySet->getPertinence(), &newPointC, &newPertinenceC); 114 | // include it 115 | this->fuzzyComposition->addPoint(newPointC, newPertinenceC); 116 | } 117 | } 118 | // if it is not a triangle non a trapeze, it is a singleton 119 | else 120 | { 121 | // include it 122 | this->fuzzyComposition->addPoint(aux->fuzzySet->getPointB(), 0.0); 123 | // include it 124 | this->fuzzyComposition->addPoint(aux->fuzzySet->getPointB(), aux->fuzzySet->getPertinence()); 125 | // include it 126 | this->fuzzyComposition->addPoint(aux->fuzzySet->getPointB(), 0.0); 127 | } 128 | // Check if it is not a "trapeze" without its right triangle or singleton, before include the point D 129 | if (aux->fuzzySet->getPointC() != aux->fuzzySet->getPointD()) 130 | { 131 | // include it 132 | this->fuzzyComposition->addPoint(aux->fuzzySet->getPointD(), 0.0); 133 | } 134 | } 135 | aux = aux->next; 136 | } 137 | // call build from FuzzyComposition for its self building 138 | this->fuzzyComposition->build(); 139 | return true; 140 | } 141 | 142 | // Method to run the calculate of FuzzyComposition and return the result 143 | float FuzzyOutput::getCrispOutput() 144 | { 145 | return this->fuzzyComposition->calculate(); 146 | } 147 | 148 | // Method to sort the FuzzySet by the reference of the point A in an ascending order 149 | // It is just a simple Bubble Sort 150 | bool FuzzyOutput::order() 151 | { 152 | // instantiating some auxiliary variables 153 | fuzzySetArray *aux1 = this->fuzzySets; 154 | fuzzySetArray *aux2 = this->fuzzySets; 155 | // while not in the end of the array, iterate 156 | while (aux1 != NULL) 157 | { 158 | // iterate again to ensure all matches, for the worst case (complet inversion) 159 | while (aux2 != NULL) 160 | { 161 | // check if not in the last element 162 | if (aux2->next != NULL) 163 | { 164 | // check if the point from the first is bigger the the second 165 | if (aux2->fuzzySet->getPointA() > aux2->next->fuzzySet->getPointA()) 166 | { 167 | // if true, swap the FuzzySet 168 | this->swap(aux2, aux2->next); 169 | } 170 | } 171 | aux2 = aux2->next; 172 | } 173 | // restarting the second auxiliary variable 174 | aux2 = this->fuzzySets; 175 | aux1 = aux1->next; 176 | } 177 | return true; 178 | } 179 | 180 | // Method to get the value (pointer) of fuzzyComposition 181 | FuzzyComposition *FuzzyOutput::getFuzzyComposition() 182 | { 183 | return this->fuzzyComposition; 184 | } 185 | 186 | // PRIVATE METHODS 187 | 188 | // Method to invert the values (references) of two FuzzySet 189 | bool FuzzyOutput::swap(fuzzySetArray *fuzzySetA, fuzzySetArray *fuzzySetB) 190 | { 191 | // put the first into an auxiliary variable 192 | FuzzySet *aux = fuzzySetA->fuzzySet; 193 | // put the second into the first 194 | fuzzySetA->fuzzySet = fuzzySetB->fuzzySet; 195 | // put the auxiliary into the second 196 | fuzzySetB->fuzzySet = aux; 197 | return true; 198 | } 199 | 200 | // Method to rebuild some point, the new point is calculated finding the intersection between two lines 201 | bool FuzzyOutput::rebuild(float x1, float y1, float x2, float y2, float x3, float y3, float x4, float y4, float *point, float *pertinence) 202 | { 203 | // help variables 204 | float denom, numera, numerb; 205 | float mua, mub; 206 | // calculate the denominator and numerator 207 | denom = (y4 - y3) * (x2 - x1) - (x4 - x3) * (y2 - y1); 208 | numera = (x4 - x3) * (y1 - y3) - (y4 - y3) * (x1 - x3); 209 | numerb = (x2 - x1) * (y1 - y3) - (y2 - y1) * (x1 - x3); 210 | // if negative, convert to positive 211 | if (denom < 0.0) 212 | { 213 | denom *= -1.0; 214 | } 215 | // If the denominator is zero or close to it, it means that the lines are parallels, so return false for intersection 216 | if (denom < EPSILON_VALUE) 217 | { 218 | // return false for intersection 219 | return false; 220 | } 221 | // if negative, convert to positive 222 | if (numera < 0.0) 223 | { 224 | numera *= -1.0; 225 | } 226 | // if negative, convert to positive 227 | if (numerb < 0.0) 228 | { 229 | numerb *= -1.0; 230 | } 231 | // verify if has intersection between the segments 232 | mua = numera / denom; 233 | mub = numerb / denom; 234 | if (mua < 0.0 || mua > 1.0 || mub < 0.0 || mub > 1.0) 235 | { 236 | // return false for intersection 237 | return false; 238 | } 239 | else 240 | { 241 | // calculate and setting the new point and pertinence 242 | *point = x1 + mua * (x2 - x1); 243 | *pertinence = y1 + mua * (y2 - y1); 244 | // return true for intersection 245 | return true; 246 | } 247 | } -------------------------------------------------------------------------------- /tests/FuzzyTest.cpp: -------------------------------------------------------------------------------- 1 | #include "gtest/gtest.h" 2 | #include "../Fuzzy.h" 3 | 4 | // ##### Tests of FuzzySet 5 | 6 | TEST(FuzzySet, getPoints) 7 | { 8 | FuzzySet *fuzzySet = new FuzzySet(0, 10, 20, 30); 9 | ASSERT_EQ(0, fuzzySet->getPointA()); 10 | ASSERT_EQ(10, fuzzySet->getPointB()); 11 | ASSERT_EQ(20, fuzzySet->getPointC()); 12 | ASSERT_EQ(30, fuzzySet->getPointD()); 13 | } 14 | 15 | TEST(FuzzySet, calculateAndGetPertinence) 16 | { 17 | FuzzySet *fuzzySet1 = new FuzzySet(0, 10, 10, 20); 18 | 19 | fuzzySet1->calculatePertinence(-5); 20 | ASSERT_FLOAT_EQ(0.0, fuzzySet1->getPertinence()); 21 | 22 | fuzzySet1->calculatePertinence(5); 23 | ASSERT_FLOAT_EQ(0.5, fuzzySet1->getPertinence()); 24 | 25 | fuzzySet1->calculatePertinence(10); 26 | ASSERT_FLOAT_EQ(1.0, fuzzySet1->getPertinence()); 27 | 28 | fuzzySet1->calculatePertinence(15); 29 | ASSERT_FLOAT_EQ(0.5, fuzzySet1->getPertinence()); 30 | 31 | fuzzySet1->calculatePertinence(25); 32 | ASSERT_FLOAT_EQ(0.0, fuzzySet1->getPertinence()); 33 | 34 | FuzzySet *fuzzySet2 = new FuzzySet(0, 0, 20, 30); 35 | 36 | fuzzySet2->calculatePertinence(-5); 37 | ASSERT_FLOAT_EQ(1.0, fuzzySet2->getPertinence()); 38 | 39 | FuzzySet *fuzzySet3 = new FuzzySet(0, 10, 20, 20); 40 | 41 | fuzzySet3->calculatePertinence(25); 42 | ASSERT_FLOAT_EQ(1.0, fuzzySet3->getPertinence()); 43 | } 44 | 45 | // ##### Tests of FuzzyInput (It tests FuzzyIO too) 46 | 47 | TEST(FuzzyInput, addFuzzySet) 48 | { 49 | FuzzyInput *fuzzyInput = new FuzzyInput(1); 50 | FuzzySet *fuzzySet = new FuzzySet(0, 10, 10, 20); 51 | ASSERT_TRUE(fuzzyInput->addFuzzySet(fuzzySet)); 52 | } 53 | 54 | TEST(FuzzyInput, setCrispInputAndGetCrispInput) 55 | { 56 | FuzzyInput *fuzzyInput = new FuzzyInput(1); 57 | fuzzyInput->setCrispInput(10.190); 58 | ASSERT_FLOAT_EQ(10.190, fuzzyInput->getCrispInput()); 59 | } 60 | 61 | TEST(FuzzyInput, calculateFuzzySetPertinences) 62 | { 63 | FuzzyInput *fuzzyInput = new FuzzyInput(1); 64 | 65 | FuzzySet *fuzzySet1 = new FuzzySet(0, 10, 10, 20); 66 | 67 | fuzzyInput->addFuzzySet(fuzzySet1); 68 | 69 | FuzzySet *fuzzySet2 = new FuzzySet(10, 20, 20, 30); 70 | 71 | fuzzyInput->addFuzzySet(fuzzySet2); 72 | 73 | fuzzyInput->setCrispInput(5); 74 | 75 | ASSERT_TRUE(fuzzyInput->calculateFuzzySetPertinences()); 76 | 77 | ASSERT_FLOAT_EQ(0.5, fuzzySet1->getPertinence()); 78 | 79 | ASSERT_FLOAT_EQ(0.0, fuzzySet2->getPertinence()); 80 | } 81 | 82 | // ##### Tests of FuzzyComposition 83 | 84 | TEST(FuzzyComposition, addPointAndCheckPoint) 85 | { 86 | FuzzyComposition *fuzzyComposition = new FuzzyComposition(); 87 | 88 | ASSERT_TRUE(fuzzyComposition->addPoint(1, 0.1)); 89 | ASSERT_TRUE(fuzzyComposition->checkPoint(1, 0.1)); 90 | 91 | ASSERT_TRUE(fuzzyComposition->addPoint(5, 0.5)); 92 | ASSERT_TRUE(fuzzyComposition->checkPoint(5, 0.5)); 93 | 94 | ASSERT_TRUE(fuzzyComposition->addPoint(9, 0.9)); 95 | ASSERT_TRUE(fuzzyComposition->checkPoint(9, 0.9)); 96 | 97 | ASSERT_FALSE(fuzzyComposition->checkPoint(5, 0.1)); 98 | } 99 | 100 | TEST(FuzzyComposition, build) 101 | { 102 | FuzzyComposition *fuzzyComposition = new FuzzyComposition(); 103 | 104 | fuzzyComposition->addPoint(0, 0); 105 | fuzzyComposition->addPoint(10, 1); 106 | fuzzyComposition->addPoint(20, 0); 107 | 108 | fuzzyComposition->addPoint(10, 0); 109 | fuzzyComposition->addPoint(20, 1); 110 | fuzzyComposition->addPoint(30, 0); 111 | 112 | ASSERT_TRUE(fuzzyComposition->build()); 113 | 114 | ASSERT_TRUE(fuzzyComposition->checkPoint(0, 0)); 115 | ASSERT_TRUE(fuzzyComposition->checkPoint(10, 1)); 116 | ASSERT_FALSE(fuzzyComposition->checkPoint(20, 0)); 117 | ASSERT_TRUE(fuzzyComposition->checkPoint(15, 0.5)); 118 | ASSERT_FALSE(fuzzyComposition->checkPoint(10, 0)); 119 | ASSERT_TRUE(fuzzyComposition->checkPoint(20, 1)); 120 | ASSERT_TRUE(fuzzyComposition->checkPoint(30, 0)); 121 | } 122 | 123 | TEST(FuzzyComposition, calculateAndEmptyAndCountPoints) 124 | { 125 | FuzzyComposition *fuzzyComposition = new FuzzyComposition(); 126 | 127 | fuzzyComposition->addPoint(25, 0); 128 | fuzzyComposition->addPoint(25, 1); 129 | fuzzyComposition->addPoint(25, 0); 130 | fuzzyComposition->build(); 131 | ASSERT_EQ(3, fuzzyComposition->countPoints()); 132 | ASSERT_FLOAT_EQ(25, fuzzyComposition->calculate()); 133 | ASSERT_TRUE(fuzzyComposition->empty()); 134 | 135 | fuzzyComposition->addPoint(10, 0); 136 | fuzzyComposition->addPoint(20, 1); 137 | fuzzyComposition->addPoint(30, 0); 138 | fuzzyComposition->build(); 139 | ASSERT_EQ(3, fuzzyComposition->countPoints()); 140 | ASSERT_FLOAT_EQ(20, fuzzyComposition->calculate()); 141 | ASSERT_TRUE(fuzzyComposition->empty()); 142 | 143 | fuzzyComposition->addPoint(20, 0); 144 | fuzzyComposition->addPoint(30, 1); 145 | fuzzyComposition->addPoint(50, 1); 146 | fuzzyComposition->addPoint(60, 0); 147 | fuzzyComposition->build(); 148 | ASSERT_EQ(4, fuzzyComposition->countPoints()); 149 | ASSERT_FLOAT_EQ(40, fuzzyComposition->calculate()); 150 | ASSERT_TRUE(fuzzyComposition->empty()); 151 | 152 | fuzzyComposition->addPoint(0, 0); 153 | fuzzyComposition->addPoint(10, 1); 154 | fuzzyComposition->addPoint(20, 0); 155 | fuzzyComposition->addPoint(10, 0); 156 | fuzzyComposition->addPoint(20, 1); 157 | fuzzyComposition->addPoint(30, 0); 158 | fuzzyComposition->addPoint(20, 0); 159 | fuzzyComposition->addPoint(30, 1); 160 | fuzzyComposition->addPoint(40, 0); 161 | fuzzyComposition->build(); 162 | ASSERT_EQ(7, fuzzyComposition->countPoints()); 163 | ASSERT_FLOAT_EQ(20, fuzzyComposition->calculate()); 164 | } 165 | 166 | // ##### Test of FuzzyOutput (It tests FuzzyIO too) 167 | 168 | TEST(FuzzyOutput, getIndex) 169 | { 170 | FuzzyOutput *fuzzyOutput = new FuzzyOutput(1); 171 | ASSERT_EQ(1, fuzzyOutput->getIndex()); 172 | } 173 | 174 | TEST(FuzzyOutput, setCrispInputAndGetCrispInput) 175 | { 176 | FuzzyOutput *fuzzyOutput = new FuzzyOutput(1); 177 | fuzzyOutput->setCrispInput(10.190); 178 | ASSERT_FLOAT_EQ(10.190, fuzzyOutput->getCrispInput()); 179 | } 180 | 181 | TEST(FuzzyOutput, addFuzzySetAndResetFuzzySets) 182 | { 183 | FuzzyOutput *fuzzyOutput = new FuzzyOutput(1); 184 | 185 | FuzzySet *fuzzySetTest = new FuzzySet(0, 10, 10, 20); 186 | 187 | ASSERT_TRUE(fuzzyOutput->addFuzzySet(fuzzySetTest)); 188 | 189 | fuzzySetTest->setPertinence(0.242); 190 | ASSERT_FLOAT_EQ(0.242, fuzzySetTest->getPertinence()); 191 | 192 | fuzzyOutput->resetFuzzySets(); 193 | 194 | ASSERT_FLOAT_EQ(0.0, fuzzySetTest->getPertinence()); 195 | } 196 | 197 | TEST(FuzzyOutput, truncateAndGetCrispOutputAndGetFuzzyComposition) 198 | { 199 | FuzzyOutput *fuzzyOutput = new FuzzyOutput(1); 200 | 201 | ASSERT_EQ(1, fuzzyOutput->getIndex()); 202 | 203 | FuzzySet *fuzzySetTest1 = new FuzzySet(0, 10, 10, 20); 204 | fuzzySetTest1->setPertinence(1); 205 | fuzzyOutput->addFuzzySet(fuzzySetTest1); 206 | 207 | FuzzySet *fuzzySetTest2 = new FuzzySet(10, 20, 20, 30); 208 | fuzzySetTest2->setPertinence(1); 209 | fuzzyOutput->addFuzzySet(fuzzySetTest2); 210 | 211 | FuzzySet *fuzzySetTest3 = new FuzzySet(20, 30, 30, 40); 212 | fuzzySetTest3->setPertinence(1); 213 | fuzzyOutput->addFuzzySet(fuzzySetTest3); 214 | 215 | ASSERT_TRUE(fuzzyOutput->truncate()); 216 | 217 | FuzzyComposition *fuzzyComposition = fuzzyOutput->getFuzzyComposition(); 218 | 219 | ASSERT_NE(nullptr, fuzzyComposition); 220 | 221 | ASSERT_EQ(8, fuzzyComposition->countPoints()); 222 | 223 | ASSERT_TRUE(fuzzyComposition->checkPoint(0, 0)); 224 | ASSERT_TRUE(fuzzyComposition->checkPoint(10, 1)); 225 | ASSERT_FALSE(fuzzyComposition->checkPoint(20, 0)); 226 | 227 | ASSERT_TRUE(fuzzyComposition->checkPoint(15, 0.5)); 228 | 229 | ASSERT_FALSE(fuzzyComposition->checkPoint(10, 0)); 230 | ASSERT_TRUE(fuzzyComposition->checkPoint(20, 1)); 231 | ASSERT_FALSE(fuzzyComposition->checkPoint(30, 0)); 232 | 233 | ASSERT_TRUE(fuzzyComposition->checkPoint(25, 0.5)); 234 | 235 | ASSERT_FALSE(fuzzyComposition->checkPoint(20, 0)); 236 | ASSERT_TRUE(fuzzyComposition->checkPoint(30, 1)); 237 | ASSERT_TRUE(fuzzyComposition->checkPoint(40, 0)); 238 | 239 | ASSERT_FLOAT_EQ(20.0, fuzzyOutput->getCrispOutput()); 240 | } 241 | 242 | // ##### Tests for FuzzyRuleAntecedent 243 | 244 | TEST(FuzzyRuleAntecedent, joinSingleAndEvaluate) 245 | { 246 | FuzzyRuleAntecedent *fuzzyRuleAntecedent = new FuzzyRuleAntecedent(); 247 | 248 | FuzzySet *fuzzySet = new FuzzySet(0, 10, 10, 20); 249 | fuzzySet->setPertinence(0.25); 250 | 251 | ASSERT_TRUE(fuzzyRuleAntecedent->joinSingle(fuzzySet)); 252 | ASSERT_FLOAT_EQ(0.25, fuzzyRuleAntecedent->evaluate()); 253 | } 254 | 255 | TEST(FuzzyRuleAntecedent, joinTwoFuzzySetAndEvaluate) 256 | { 257 | FuzzySet *fuzzySet1 = new FuzzySet(0, 10, 10, 20); 258 | fuzzySet1->setPertinence(0.25); 259 | FuzzySet *fuzzySet2 = new FuzzySet(10, 20, 20, 30); 260 | fuzzySet2->setPertinence(0.75); 261 | 262 | FuzzyRuleAntecedent *fuzzyRuleAntecedent1 = new FuzzyRuleAntecedent(); 263 | ASSERT_TRUE(fuzzyRuleAntecedent1->joinWithAND(fuzzySet1, fuzzySet2)); 264 | ASSERT_FLOAT_EQ(0.25, fuzzyRuleAntecedent1->evaluate()); 265 | 266 | FuzzyRuleAntecedent *fuzzyRuleAntecedent2 = new FuzzyRuleAntecedent(); 267 | ASSERT_TRUE(fuzzyRuleAntecedent2->joinWithOR(fuzzySet1, fuzzySet2)); 268 | ASSERT_FLOAT_EQ(0.75, fuzzyRuleAntecedent2->evaluate()); 269 | } 270 | 271 | TEST(FuzzyRuleAntecedent, joinOneFuzzySetAndOneFuzzyAntecedentAndEvaluate) 272 | { 273 | FuzzySet *fuzzySet1 = new FuzzySet(0, 10, 10, 20); 274 | fuzzySet1->setPertinence(0.25); 275 | 276 | FuzzyRuleAntecedent *fuzzyRuleAntecedent1 = new FuzzyRuleAntecedent(); 277 | FuzzySet *fuzzySet2 = new FuzzySet(10, 20, 20, 30); 278 | fuzzySet2->setPertinence(0.75); 279 | fuzzyRuleAntecedent1->joinSingle(fuzzySet2); 280 | 281 | FuzzyRuleAntecedent *fuzzyRuleAntecedent2 = new FuzzyRuleAntecedent(); 282 | ASSERT_TRUE(fuzzyRuleAntecedent2->joinWithAND(fuzzySet1, fuzzyRuleAntecedent1)); 283 | ASSERT_FLOAT_EQ(0.25, fuzzyRuleAntecedent2->evaluate()); 284 | 285 | FuzzyRuleAntecedent *fuzzyRuleAntecedent3 = new FuzzyRuleAntecedent(); 286 | ASSERT_TRUE(fuzzyRuleAntecedent3->joinWithAND(fuzzyRuleAntecedent1, fuzzySet1)); 287 | ASSERT_FLOAT_EQ(0.25, fuzzyRuleAntecedent3->evaluate()); 288 | 289 | FuzzyRuleAntecedent *fuzzyRuleAntecedent4 = new FuzzyRuleAntecedent(); 290 | ASSERT_TRUE(fuzzyRuleAntecedent4->joinWithOR(fuzzySet1, fuzzyRuleAntecedent1)); 291 | ASSERT_FLOAT_EQ(0.75, fuzzyRuleAntecedent4->evaluate()); 292 | 293 | FuzzyRuleAntecedent *fuzzyRuleAntecedent5 = new FuzzyRuleAntecedent(); 294 | ASSERT_TRUE(fuzzyRuleAntecedent5->joinWithOR(fuzzyRuleAntecedent1, fuzzySet1)); 295 | ASSERT_FLOAT_EQ(0.75, fuzzyRuleAntecedent5->evaluate()); 296 | } 297 | 298 | TEST(FuzzyRuleAntecedent, joinTwoFuzzyAntecedentAndEvaluate) 299 | { 300 | FuzzyRuleAntecedent *fuzzyRuleAntecedent1 = new FuzzyRuleAntecedent(); 301 | FuzzySet *fuzzySet1 = new FuzzySet(0, 10, 10, 20); 302 | fuzzySet1->setPertinence(0.25); 303 | fuzzyRuleAntecedent1->joinSingle(fuzzySet1); 304 | 305 | FuzzyRuleAntecedent *fuzzyRuleAntecedent2 = new FuzzyRuleAntecedent(); 306 | FuzzySet *fuzzySet2 = new FuzzySet(10, 20, 20, 30); 307 | fuzzySet2->setPertinence(0.75); 308 | FuzzySet *fuzzySet3 = new FuzzySet(30, 40, 40, 50); 309 | fuzzySet3->setPertinence(0.5); 310 | fuzzyRuleAntecedent2->joinWithOR(fuzzySet2, fuzzySet3); 311 | 312 | FuzzyRuleAntecedent *fuzzyRuleAntecedent3 = new FuzzyRuleAntecedent(); 313 | ASSERT_TRUE(fuzzyRuleAntecedent3->joinWithAND(fuzzyRuleAntecedent1, fuzzyRuleAntecedent2)); 314 | ASSERT_FLOAT_EQ(0.25, fuzzyRuleAntecedent3->evaluate()); 315 | 316 | FuzzyRuleAntecedent *fuzzyRuleAntecedent4 = new FuzzyRuleAntecedent(); 317 | ASSERT_TRUE(fuzzyRuleAntecedent4->joinWithOR(fuzzyRuleAntecedent1, fuzzyRuleAntecedent2)); 318 | ASSERT_FLOAT_EQ(0.75, fuzzyRuleAntecedent4->evaluate()); 319 | } 320 | 321 | // ##### Tests for FuzzyRuleConsequent 322 | 323 | TEST(FuzzyRuleConsequent, addOutputAndEvaluate) 324 | { 325 | FuzzyRuleConsequent *fuzzyRuleConsequent = new FuzzyRuleConsequent(); 326 | 327 | FuzzySet *fuzzySet1 = new FuzzySet(0, 10, 10, 20); 328 | FuzzySet *fuzzySet2 = new FuzzySet(10, 20, 20, 30); 329 | 330 | ASSERT_TRUE(fuzzyRuleConsequent->addOutput(fuzzySet1)); 331 | 332 | fuzzyRuleConsequent->addOutput(fuzzySet2); 333 | 334 | ASSERT_TRUE(fuzzyRuleConsequent->evaluate(0.5)); 335 | 336 | ASSERT_FLOAT_EQ(0.5, fuzzySet1->getPertinence()); 337 | ASSERT_FLOAT_EQ(0.5, fuzzySet2->getPertinence()); 338 | } 339 | 340 | // ##### Tests for FuzzyRule 341 | 342 | TEST(FuzzyRule, getIndexAndEvaluateExpressionAndIsFired) 343 | { 344 | FuzzyRuleAntecedent *fuzzyRuleAntecedent1 = new FuzzyRuleAntecedent(); 345 | FuzzySet *fuzzySet = new FuzzySet(0, 10, 10, 20); 346 | fuzzySet->setPertinence(0.75); 347 | fuzzyRuleAntecedent1->joinSingle(fuzzySet); 348 | 349 | FuzzyRuleAntecedent *fuzzyRuleAntecedent2 = new FuzzyRuleAntecedent(); 350 | FuzzySet *fuzzySet2 = new FuzzySet(0, 10, 10, 20); 351 | fuzzySet2->setPertinence(0.25); 352 | fuzzyRuleAntecedent2->joinSingle(fuzzySet2); 353 | 354 | FuzzyRuleAntecedent *fuzzyRuleAntecedent3 = new FuzzyRuleAntecedent(); 355 | fuzzyRuleAntecedent3->joinWithAND(fuzzyRuleAntecedent1, fuzzyRuleAntecedent2); 356 | 357 | FuzzyRuleConsequent *fuzzyRuleConsequent = new FuzzyRuleConsequent(); 358 | FuzzySet *fuzzySet3 = new FuzzySet(0, 10, 10, 20); 359 | fuzzyRuleConsequent->addOutput(fuzzySet3); 360 | 361 | FuzzyRule *fuzzyRule = new FuzzyRule(1, fuzzyRuleAntecedent3, fuzzyRuleConsequent); 362 | 363 | ASSERT_EQ(1, fuzzyRule->getIndex()); 364 | ASSERT_FALSE(fuzzyRule->isFired()); 365 | 366 | ASSERT_TRUE(fuzzyRule->evaluateExpression()); 367 | 368 | ASSERT_TRUE(fuzzyRule->isFired()); 369 | } 370 | 371 | // ##### Tests for Fuzzy 372 | 373 | TEST(Fuzzy, addFuzzyInput) 374 | { 375 | Fuzzy *fuzzy = new Fuzzy(); 376 | 377 | FuzzyInput *fuzzyInput = new FuzzyInput(1); 378 | 379 | FuzzySet *fuzzySet1 = new FuzzySet(0, 10, 10, 20); 380 | fuzzyInput->addFuzzySet(fuzzySet1); 381 | FuzzySet *fuzzySet2 = new FuzzySet(10, 20, 20, 30); 382 | fuzzyInput->addFuzzySet(fuzzySet2); 383 | FuzzySet *fuzzySet3 = new FuzzySet(20, 30, 30, 40); 384 | fuzzyInput->addFuzzySet(fuzzySet3); 385 | 386 | ASSERT_TRUE(fuzzy->addFuzzyInput(fuzzyInput)); 387 | } 388 | 389 | TEST(Fuzzy, addFuzzyOutput) 390 | { 391 | Fuzzy *fuzzy = new Fuzzy(); 392 | 393 | FuzzyOutput *fuzzyOutput = new FuzzyOutput(1); 394 | 395 | FuzzySet *fuzzySet1 = new FuzzySet(0, 10, 10, 20); 396 | fuzzyOutput->addFuzzySet(fuzzySet1); 397 | FuzzySet *fuzzySet2 = new FuzzySet(10, 20, 20, 30); 398 | fuzzyOutput->addFuzzySet(fuzzySet2); 399 | FuzzySet *fuzzySet3 = new FuzzySet(20, 30, 30, 40); 400 | fuzzyOutput->addFuzzySet(fuzzySet3); 401 | 402 | ASSERT_TRUE(fuzzy->addFuzzyOutput(fuzzyOutput)); 403 | } 404 | 405 | TEST(Fuzzy, addFuzzyRule) 406 | { 407 | Fuzzy *fuzzy = new Fuzzy(); 408 | 409 | FuzzyRuleAntecedent *fuzzyRuleAntecedent1 = new FuzzyRuleAntecedent(); 410 | FuzzySet *fuzzySet1 = new FuzzySet(0, 10, 10, 20); 411 | fuzzySet1->setPertinence(0.25); 412 | fuzzyRuleAntecedent1->joinSingle(fuzzySet1); 413 | 414 | FuzzyRuleAntecedent *fuzzyRuleAntecedent2 = new FuzzyRuleAntecedent(); 415 | FuzzySet *fuzzySet2 = new FuzzySet(0, 10, 10, 20); 416 | fuzzySet2->setPertinence(0.75); 417 | fuzzyRuleAntecedent2->joinSingle(fuzzySet2); 418 | 419 | FuzzyRuleAntecedent *fuzzyRuleAntecedent3 = new FuzzyRuleAntecedent(); 420 | fuzzyRuleAntecedent3->joinWithAND(fuzzyRuleAntecedent1, fuzzyRuleAntecedent2); 421 | 422 | FuzzyRuleConsequent *fuzzyRuleConsequent = new FuzzyRuleConsequent(); 423 | FuzzySet *fuzzySet3 = new FuzzySet(0, 10, 10, 20); 424 | fuzzyRuleConsequent->addOutput(fuzzySet3); 425 | 426 | FuzzyRule *fuzzyRule = new FuzzyRule(1, fuzzyRuleAntecedent3, fuzzyRuleConsequent); 427 | 428 | ASSERT_TRUE(fuzzy->addFuzzyRule(fuzzyRule)); 429 | } 430 | 431 | TEST(Fuzzy, setInputAndFuzzifyAndIsFiredRuleAndDefuzzify) 432 | { 433 | Fuzzy *fuzzy = new Fuzzy(); 434 | 435 | // FuzzyInput 436 | FuzzyInput *temperature = new FuzzyInput(1); 437 | 438 | FuzzySet *low = new FuzzySet(0, 10, 10, 20); 439 | temperature->addFuzzySet(low); 440 | FuzzySet *mean = new FuzzySet(10, 20, 30, 40); 441 | temperature->addFuzzySet(mean); 442 | FuzzySet *high = new FuzzySet(30, 40, 40, 50); 443 | temperature->addFuzzySet(high); 444 | 445 | fuzzy->addFuzzyInput(temperature); 446 | 447 | // FuzzyOutput 448 | FuzzyOutput *climate = new FuzzyOutput(1); 449 | 450 | FuzzySet *cold = new FuzzySet(0, 10, 10, 20); 451 | climate->addFuzzySet(cold); 452 | FuzzySet *good = new FuzzySet(10, 20, 30, 40); 453 | climate->addFuzzySet(good); 454 | FuzzySet *hot = new FuzzySet(30, 40, 40, 50); 455 | climate->addFuzzySet(hot); 456 | 457 | fuzzy->addFuzzyOutput(climate); 458 | 459 | // Building FuzzyRule 460 | FuzzyRuleAntecedent *ifTemperatureLow = new FuzzyRuleAntecedent(); 461 | ifTemperatureLow->joinSingle(low); 462 | FuzzyRuleConsequent *thenClimateCold = new FuzzyRuleConsequent(); 463 | thenClimateCold->addOutput(cold); 464 | 465 | FuzzyRule *fuzzyRule1 = new FuzzyRule(1, ifTemperatureLow, thenClimateCold); 466 | fuzzy->addFuzzyRule(fuzzyRule1); 467 | 468 | // Building FuzzyRule 469 | FuzzyRuleAntecedent *ifTemperatureMean = new FuzzyRuleAntecedent(); 470 | ifTemperatureMean->joinSingle(mean); 471 | FuzzyRuleConsequent *thenClimateGood = new FuzzyRuleConsequent(); 472 | thenClimateGood->addOutput(good); 473 | 474 | FuzzyRule *fuzzyRule2 = new FuzzyRule(2, ifTemperatureMean, thenClimateGood); 475 | fuzzy->addFuzzyRule(fuzzyRule2); 476 | 477 | // Building FuzzyRule 478 | FuzzyRuleAntecedent *ifTemperatureHigh = new FuzzyRuleAntecedent(); 479 | ifTemperatureHigh->joinSingle(high); 480 | FuzzyRuleConsequent *thenClimateHot = new FuzzyRuleConsequent(); 481 | thenClimateHot->addOutput(cold); 482 | 483 | FuzzyRule *fuzzyRule3 = new FuzzyRule(3, ifTemperatureHigh, thenClimateHot); 484 | fuzzy->addFuzzyRule(fuzzyRule3); 485 | 486 | ASSERT_TRUE(fuzzy->setInput(1, 15)); 487 | 488 | ASSERT_TRUE(fuzzy->fuzzify()); 489 | 490 | ASSERT_TRUE(fuzzy->isFiredRule(1)); 491 | ASSERT_TRUE(fuzzy->isFiredRule(2)); 492 | ASSERT_FALSE(fuzzy->isFiredRule(3)); 493 | 494 | ASSERT_FLOAT_EQ(19.375, fuzzy->defuzzify(1)); 495 | } 496 | 497 | // ##### Tests from explanation Fuzzy System 498 | 499 | // From: https://www.massey.ac.nz/~nhreyes/MASSEY/159741/Lectures/Lec2012-3-159741-FuzzyLogic-v.2.pdf 500 | TEST(Fuzzy, testFromLectureSystemsOne) 501 | { 502 | Fuzzy *fuzzy = new Fuzzy(); 503 | 504 | // FuzzyInput 505 | FuzzyInput *size = new FuzzyInput(1); 506 | 507 | FuzzySet *smallSize = new FuzzySet(0, 0, 0, 10); 508 | size->addFuzzySet(smallSize); 509 | FuzzySet *largeSize = new FuzzySet(0, 10, 10, 10); 510 | size->addFuzzySet(largeSize); 511 | 512 | fuzzy->addFuzzyInput(size); 513 | 514 | // FuzzyInput 515 | FuzzyInput *weight = new FuzzyInput(2); 516 | 517 | FuzzySet *smallWeight = new FuzzySet(0, 0, 0, 100); 518 | weight->addFuzzySet(smallWeight); 519 | FuzzySet *largeWeight = new FuzzySet(0, 100, 100, 100); 520 | weight->addFuzzySet(largeWeight); 521 | 522 | fuzzy->addFuzzyInput(weight); 523 | 524 | // FuzzyOutput 525 | FuzzyOutput *quality = new FuzzyOutput(1); 526 | 527 | FuzzySet *bad = new FuzzySet(0, 0, 0, 0.5); 528 | quality->addFuzzySet(bad); 529 | FuzzySet *medium = new FuzzySet(0, 0.5, 0.5, 1.0); 530 | quality->addFuzzySet(medium); 531 | FuzzySet *good = new FuzzySet(0.5, 1.0, 1.0, 1.0); 532 | quality->addFuzzySet(good); 533 | 534 | fuzzy->addFuzzyOutput(quality); 535 | 536 | // Building FuzzyRule 537 | FuzzyRuleAntecedent *ifSizeSmallAndWeightSmall = new FuzzyRuleAntecedent(); 538 | ifSizeSmallAndWeightSmall->joinWithAND(smallSize, smallWeight); 539 | FuzzyRuleConsequent *thenQualityBad = new FuzzyRuleConsequent(); 540 | thenQualityBad->addOutput(bad); 541 | FuzzyRule *fuzzyRule1 = new FuzzyRule(1, ifSizeSmallAndWeightSmall, thenQualityBad); 542 | fuzzy->addFuzzyRule(fuzzyRule1); 543 | 544 | // Building FuzzyRule 545 | FuzzyRuleAntecedent *ifSizeSmallAndWeightLarge = new FuzzyRuleAntecedent(); 546 | ifSizeSmallAndWeightLarge->joinWithAND(smallSize, largeWeight); 547 | FuzzyRuleConsequent *thenQualityMedium1 = new FuzzyRuleConsequent(); 548 | thenQualityMedium1->addOutput(medium); 549 | FuzzyRule *fuzzyRule2 = new FuzzyRule(2, ifSizeSmallAndWeightLarge, thenQualityMedium1); 550 | fuzzy->addFuzzyRule(fuzzyRule2); 551 | 552 | // Building FuzzyRule 553 | FuzzyRuleAntecedent *ifSizeLargeAndWeightSmall = new FuzzyRuleAntecedent(); 554 | ifSizeLargeAndWeightSmall->joinWithAND(largeSize, smallWeight); 555 | FuzzyRuleConsequent *thenQualityMedium2 = new FuzzyRuleConsequent(); 556 | thenQualityMedium2->addOutput(medium); 557 | FuzzyRule *fuzzyRule3 = new FuzzyRule(3, ifSizeLargeAndWeightSmall, thenQualityMedium2); 558 | fuzzy->addFuzzyRule(fuzzyRule3); 559 | 560 | // Building FuzzyRule 561 | FuzzyRuleAntecedent *ifSizeLargeAndWeightLarge = new FuzzyRuleAntecedent(); 562 | ifSizeLargeAndWeightLarge->joinWithAND(largeSize, largeWeight); 563 | FuzzyRuleConsequent *thenQualityGood = new FuzzyRuleConsequent(); 564 | thenQualityGood->addOutput(good); 565 | FuzzyRule *fuzzyRule4 = new FuzzyRule(4, ifSizeLargeAndWeightLarge, thenQualityGood); 566 | fuzzy->addFuzzyRule(fuzzyRule4); 567 | 568 | // run it 569 | fuzzy->setInput(1, 2); 570 | fuzzy->setInput(2, 25); 571 | fuzzy->fuzzify(); 572 | 573 | ASSERT_FLOAT_EQ(0.75, ifSizeSmallAndWeightSmall->evaluate()); 574 | ASSERT_FLOAT_EQ(0.25, ifSizeSmallAndWeightLarge->evaluate()); 575 | ASSERT_FLOAT_EQ(0.2, ifSizeLargeAndWeightSmall->evaluate()); 576 | ASSERT_FLOAT_EQ(0.2, ifSizeLargeAndWeightLarge->evaluate()); 577 | 578 | ASSERT_FLOAT_EQ(0.37692466, fuzzy->defuzzify(1)); // 0.3698 on the paper 579 | } 580 | 581 | // From: http://citeseerx.ist.psu.edu/viewdoc/download?doi=10.1.1.486.1238&rep=rep1&type=pdf 582 | TEST(Fuzzy, testFromLectureSystemsTwo) 583 | { 584 | Fuzzy *fuzzy = new Fuzzy(); 585 | 586 | // FuzzyInput 587 | FuzzyInput *temperature = new FuzzyInput(1); 588 | 589 | FuzzySet *veryLow = new FuzzySet(-5, -5, -5, 15); 590 | temperature->addFuzzySet(veryLow); 591 | FuzzySet *low = new FuzzySet(10, 20, 20, 30); 592 | temperature->addFuzzySet(low); 593 | FuzzySet *high = new FuzzySet(25, 30, 30, 35); 594 | temperature->addFuzzySet(high); 595 | FuzzySet *veryHigh = new FuzzySet(30, 50, 50, 50); 596 | temperature->addFuzzySet(veryHigh); 597 | 598 | fuzzy->addFuzzyInput(temperature); 599 | 600 | // FuzzyInput 601 | FuzzyInput *humidity = new FuzzyInput(2); 602 | 603 | FuzzySet *dry = new FuzzySet(-5, -5, -5, 30); 604 | humidity->addFuzzySet(dry); 605 | FuzzySet *comfortable = new FuzzySet(20, 35, 35, 50); 606 | humidity->addFuzzySet(comfortable); 607 | FuzzySet *humid = new FuzzySet(40, 55, 55, 70); 608 | humidity->addFuzzySet(humid); 609 | FuzzySet *sticky = new FuzzySet(60, 100, 100, 100); 610 | humidity->addFuzzySet(sticky); 611 | 612 | fuzzy->addFuzzyInput(humidity); 613 | 614 | // FuzzyOutput 615 | FuzzyOutput *speed = new FuzzyOutput(1); 616 | 617 | FuzzySet *off = new FuzzySet(0, 0, 0, 0); 618 | speed->addFuzzySet(off); 619 | FuzzySet *lowHumidity = new FuzzySet(30, 45, 45, 60); 620 | speed->addFuzzySet(lowHumidity); 621 | FuzzySet *medium = new FuzzySet(50, 65, 65, 80); 622 | speed->addFuzzySet(medium); 623 | FuzzySet *fast = new FuzzySet(70, 90, 95, 95); 624 | speed->addFuzzySet(fast); 625 | 626 | fuzzy->addFuzzyOutput(speed); 627 | 628 | // Building FuzzyRule 629 | FuzzyRuleAntecedent *ifVeryLowAndDry = new FuzzyRuleAntecedent(); 630 | ifVeryLowAndDry->joinWithAND(veryLow, dry); 631 | FuzzyRuleConsequent *thenOff1 = new FuzzyRuleConsequent(); 632 | thenOff1->addOutput(off); 633 | FuzzyRule *fuzzyRule1 = new FuzzyRule(1, ifVeryLowAndDry, thenOff1); 634 | fuzzy->addFuzzyRule(fuzzyRule1); 635 | 636 | // Building FuzzyRule 637 | FuzzyRuleAntecedent *ifVeryLowAndComfortable = new FuzzyRuleAntecedent(); 638 | ifVeryLowAndComfortable->joinWithAND(veryLow, comfortable); 639 | FuzzyRuleConsequent *thenOff2 = new FuzzyRuleConsequent(); 640 | thenOff2->addOutput(off); 641 | FuzzyRule *fuzzyRule2 = new FuzzyRule(2, ifVeryLowAndComfortable, thenOff2); 642 | fuzzy->addFuzzyRule(fuzzyRule2); 643 | 644 | // Building FuzzyRule 645 | FuzzyRuleAntecedent *ifVeryLowAndHumid = new FuzzyRuleAntecedent(); 646 | ifVeryLowAndHumid->joinWithAND(veryLow, humid); 647 | FuzzyRuleConsequent *thenOff3 = new FuzzyRuleConsequent(); 648 | thenOff3->addOutput(off); 649 | FuzzyRule *fuzzyRule3 = new FuzzyRule(3, ifVeryLowAndHumid, thenOff3); 650 | fuzzy->addFuzzyRule(fuzzyRule3); 651 | 652 | // Building FuzzyRule 653 | FuzzyRuleAntecedent *ifVeryLowAndSticky = new FuzzyRuleAntecedent(); 654 | ifVeryLowAndSticky->joinWithAND(veryLow, sticky); 655 | FuzzyRuleConsequent *thenLow1 = new FuzzyRuleConsequent(); 656 | thenLow1->addOutput(lowHumidity); 657 | FuzzyRule *fuzzyRule4 = new FuzzyRule(4, ifVeryLowAndSticky, thenLow1); 658 | fuzzy->addFuzzyRule(fuzzyRule4); 659 | 660 | // Building FuzzyRule 661 | FuzzyRuleAntecedent *ifLowAndDry = new FuzzyRuleAntecedent(); 662 | ifLowAndDry->joinWithAND(low, dry); 663 | FuzzyRuleConsequent *thenOff4 = new FuzzyRuleConsequent(); 664 | thenOff4->addOutput(off); 665 | FuzzyRule *fuzzyRule5 = new FuzzyRule(5, ifLowAndDry, thenOff4); 666 | fuzzy->addFuzzyRule(fuzzyRule5); 667 | 668 | // Building FuzzyRule 669 | FuzzyRuleAntecedent *ifLowAndComfortable = new FuzzyRuleAntecedent(); 670 | ifLowAndComfortable->joinWithAND(low, comfortable); 671 | FuzzyRuleConsequent *thenOff5 = new FuzzyRuleConsequent(); 672 | thenOff5->addOutput(off); 673 | FuzzyRule *fuzzyRule6 = new FuzzyRule(6, ifLowAndComfortable, thenOff5); 674 | fuzzy->addFuzzyRule(fuzzyRule6); 675 | 676 | // Building FuzzyRule 677 | FuzzyRuleAntecedent *ifLowAndHumid = new FuzzyRuleAntecedent(); 678 | ifLowAndHumid->joinWithAND(low, humid); 679 | FuzzyRuleConsequent *thenLow2 = new FuzzyRuleConsequent(); 680 | thenLow2->addOutput(lowHumidity); 681 | FuzzyRule *fuzzyRule7 = new FuzzyRule(7, ifLowAndHumid, thenLow2); 682 | fuzzy->addFuzzyRule(fuzzyRule7); 683 | 684 | // Building FuzzyRule 685 | FuzzyRuleAntecedent *ifLowAndSticky = new FuzzyRuleAntecedent(); 686 | ifLowAndSticky->joinWithAND(low, sticky); 687 | FuzzyRuleConsequent *thenMedium1 = new FuzzyRuleConsequent(); 688 | thenMedium1->addOutput(medium); 689 | FuzzyRule *fuzzyRule8 = new FuzzyRule(8, ifLowAndSticky, thenMedium1); 690 | fuzzy->addFuzzyRule(fuzzyRule8); 691 | 692 | // Building FuzzyRule 693 | FuzzyRuleAntecedent *ifHighAndDry = new FuzzyRuleAntecedent(); 694 | ifHighAndDry->joinWithAND(high, dry); 695 | FuzzyRuleConsequent *thenLow3 = new FuzzyRuleConsequent(); 696 | thenLow3->addOutput(lowHumidity); 697 | FuzzyRule *fuzzyRule9 = new FuzzyRule(9, ifHighAndDry, thenLow3); 698 | fuzzy->addFuzzyRule(fuzzyRule9); 699 | 700 | // Building FuzzyRule 701 | FuzzyRuleAntecedent *ifHighAndComfortable = new FuzzyRuleAntecedent(); 702 | ifHighAndComfortable->joinWithAND(high, comfortable); 703 | FuzzyRuleConsequent *thenMedium2 = new FuzzyRuleConsequent(); 704 | thenMedium2->addOutput(medium); 705 | FuzzyRule *fuzzyRule10 = new FuzzyRule(10, ifHighAndComfortable, thenMedium2); 706 | fuzzy->addFuzzyRule(fuzzyRule10); 707 | 708 | // Building FuzzyRule 709 | FuzzyRuleAntecedent *ifHighAndHumid = new FuzzyRuleAntecedent(); 710 | ifHighAndHumid->joinWithAND(high, humid); 711 | FuzzyRuleConsequent *thenFast1 = new FuzzyRuleConsequent(); 712 | thenFast1->addOutput(fast); 713 | FuzzyRule *fuzzyRule11 = new FuzzyRule(11, ifHighAndHumid, thenFast1); 714 | fuzzy->addFuzzyRule(fuzzyRule11); 715 | 716 | // Building FuzzyRule 717 | FuzzyRuleAntecedent *ifHighAndSticky = new FuzzyRuleAntecedent(); 718 | ifHighAndSticky->joinWithAND(high, sticky); 719 | FuzzyRuleConsequent *thenFast2 = new FuzzyRuleConsequent(); 720 | thenFast2->addOutput(fast); 721 | FuzzyRule *fuzzyRule12 = new FuzzyRule(12, ifHighAndSticky, thenFast2); 722 | fuzzy->addFuzzyRule(fuzzyRule12); 723 | 724 | // Building FuzzyRule 725 | FuzzyRuleAntecedent *ifVeryHighAndDry = new FuzzyRuleAntecedent(); 726 | ifVeryHighAndDry->joinWithAND(veryHigh, dry); 727 | FuzzyRuleConsequent *thenMedium3 = new FuzzyRuleConsequent(); 728 | thenMedium3->addOutput(medium); 729 | FuzzyRule *fuzzyRule13 = new FuzzyRule(13, ifVeryHighAndDry, thenMedium3); 730 | fuzzy->addFuzzyRule(fuzzyRule13); 731 | 732 | // Building FuzzyRule 733 | FuzzyRuleAntecedent *ifVeryHighAndComfortable = new FuzzyRuleAntecedent(); 734 | ifVeryHighAndComfortable->joinWithAND(veryHigh, comfortable); 735 | FuzzyRuleConsequent *thenFast3 = new FuzzyRuleConsequent(); 736 | thenFast3->addOutput(fast); 737 | FuzzyRule *fuzzyRule14 = new FuzzyRule(14, ifVeryHighAndComfortable, thenFast3); 738 | fuzzy->addFuzzyRule(fuzzyRule14); 739 | 740 | // Building FuzzyRule 741 | FuzzyRuleAntecedent *ifVeryHighAndHumid = new FuzzyRuleAntecedent(); 742 | ifVeryHighAndHumid->joinWithAND(veryHigh, humid); 743 | FuzzyRuleConsequent *thenFast4 = new FuzzyRuleConsequent(); 744 | thenFast4->addOutput(fast); 745 | FuzzyRule *fuzzyRule15 = new FuzzyRule(15, ifVeryHighAndHumid, thenFast4); 746 | fuzzy->addFuzzyRule(fuzzyRule15); 747 | 748 | // Building FuzzyRule 749 | FuzzyRuleAntecedent *ifVeryHighAndSticky = new FuzzyRuleAntecedent(); 750 | ifVeryHighAndSticky->joinWithAND(veryHigh, sticky); 751 | FuzzyRuleConsequent *thenFast5 = new FuzzyRuleConsequent(); 752 | thenFast5->addOutput(fast); 753 | FuzzyRule *fuzzyRule16 = new FuzzyRule(16, ifVeryHighAndSticky, thenFast5); 754 | fuzzy->addFuzzyRule(fuzzyRule16); 755 | 756 | // run it 757 | fuzzy->setInput(1, 20); 758 | fuzzy->setInput(2, 65); 759 | fuzzy->fuzzify(); 760 | 761 | ASSERT_FLOAT_EQ(50.568535, fuzzy->defuzzify(1)); // This value was not extracted from the paper 762 | } 763 | 764 | // ##### Tests from real systems, received from eFLL users 765 | 766 | // From miss Casco (Paraguay) 767 | TEST(Fuzzy, testFromLibraryUsersSystemsCasco) 768 | { 769 | Fuzzy *fuzzy = new Fuzzy(); 770 | 771 | // FuzzyInput 772 | FuzzyInput *humedad = new FuzzyInput(1); 773 | 774 | FuzzySet *seco = new FuzzySet(0, 0, 0, 42.5); 775 | humedad->addFuzzySet(seco); 776 | FuzzySet *humedo = new FuzzySet(37.5, 60, 60, 82.5); 777 | humedad->addFuzzySet(humedo); 778 | FuzzySet *encharcado = new FuzzySet(77.5, 100, 100, 100); 779 | humedad->addFuzzySet(encharcado); 780 | 781 | fuzzy->addFuzzyInput(humedad); 782 | 783 | // FuzzyInput 784 | FuzzyInput *temperatura = new FuzzyInput(2); 785 | 786 | FuzzySet *frio = new FuzzySet(-5, -5, -5, 12.5); 787 | temperatura->addFuzzySet(frio); 788 | FuzzySet *templado = new FuzzySet(7.5, 17.5, 17.5, 27.5); 789 | temperatura->addFuzzySet(templado); 790 | FuzzySet *calor = new FuzzySet(22.5, 45, 45, 45); 791 | temperatura->addFuzzySet(calor); 792 | 793 | fuzzy->addFuzzyInput(temperatura); 794 | 795 | // FuzzyInput 796 | FuzzyInput *mes = new FuzzyInput(3); 797 | 798 | FuzzySet *verano = new FuzzySet(0, 0, 0, 3.5); 799 | mes->addFuzzySet(verano); 800 | FuzzySet *otono = new FuzzySet(2.5, 4.5, 4.5, 6.5); 801 | mes->addFuzzySet(otono); 802 | FuzzySet *invierno = new FuzzySet(5.5, 7.5, 7.5, 9.5); 803 | mes->addFuzzySet(invierno); 804 | FuzzySet *primavera = new FuzzySet(8.5, 12, 12, 12); 805 | mes->addFuzzySet(primavera); 806 | 807 | fuzzy->addFuzzyInput(mes); 808 | 809 | // FuzzyOutput 810 | FuzzyOutput *tiempo = new FuzzyOutput(1); 811 | 812 | FuzzySet *nada = new FuzzySet(0, 0, 0, 0); 813 | tiempo->addFuzzySet(nada); 814 | FuzzySet *muyPoco = new FuzzySet(0, 0, 0, 5.5); 815 | tiempo->addFuzzySet(muyPoco); 816 | FuzzySet *poco = new FuzzySet(4.5, 7.5, 7.5, 10.5); 817 | tiempo->addFuzzySet(poco); 818 | FuzzySet *medio = new FuzzySet(9.5, 12.5, 12.5, 15.5); 819 | tiempo->addFuzzySet(medio); 820 | FuzzySet *bastante = new FuzzySet(14.5, 17.5, 17.5, 20.5); 821 | tiempo->addFuzzySet(bastante); 822 | FuzzySet *mucho = new FuzzySet(19.5, 22.5, 22.5, 25.5); 823 | tiempo->addFuzzySet(mucho); 824 | FuzzySet *muchisimo = new FuzzySet(24.5, 30, 30, 30); 825 | tiempo->addFuzzySet(muchisimo); 826 | 827 | fuzzy->addFuzzyOutput(tiempo); 828 | 829 | // ############## Rule 1 830 | FuzzyRuleAntecedent *fuzzyAntecedentA_1 = new FuzzyRuleAntecedent(); 831 | fuzzyAntecedentA_1->joinWithAND(seco, frio); 832 | FuzzyRuleAntecedent *fuzzyAntecedentB_1 = new FuzzyRuleAntecedent(); 833 | fuzzyAntecedentB_1->joinWithAND(fuzzyAntecedentA_1, verano); 834 | FuzzyRuleConsequent *fuzzyConsequent_1 = new FuzzyRuleConsequent(); 835 | fuzzyConsequent_1->addOutput(medio); 836 | 837 | FuzzyRule *fuzzyRule_1 = new FuzzyRule(1, fuzzyAntecedentB_1, fuzzyConsequent_1); 838 | fuzzy->addFuzzyRule(fuzzyRule_1); 839 | 840 | // ############## Rule 2 841 | FuzzyRuleAntecedent *fuzzyAntecedentA_2 = new FuzzyRuleAntecedent(); 842 | fuzzyAntecedentA_2->joinWithAND(seco, frio); 843 | FuzzyRuleAntecedent *fuzzyAntecedentB_2 = new FuzzyRuleAntecedent(); 844 | fuzzyAntecedentB_2->joinWithAND(fuzzyAntecedentA_2, otono); 845 | FuzzyRuleConsequent *fuzzyConsequent_2 = new FuzzyRuleConsequent(); 846 | fuzzyConsequent_2->addOutput(muyPoco); 847 | 848 | FuzzyRule *fuzzyRule_2 = new FuzzyRule(2, fuzzyAntecedentB_2, fuzzyConsequent_2); 849 | fuzzy->addFuzzyRule(fuzzyRule_2); 850 | 851 | // ############## Rule 3 852 | FuzzyRuleAntecedent *fuzzyAntecedentA_3 = new FuzzyRuleAntecedent(); 853 | fuzzyAntecedentA_3->joinWithAND(seco, frio); 854 | FuzzyRuleAntecedent *fuzzyAntecedentB_3 = new FuzzyRuleAntecedent(); 855 | fuzzyAntecedentB_3->joinWithAND(fuzzyAntecedentA_3, invierno); 856 | FuzzyRuleConsequent *fuzzyConsequent_3 = new FuzzyRuleConsequent(); 857 | fuzzyConsequent_3->addOutput(muyPoco); 858 | 859 | FuzzyRule *fuzzyRule_3 = new FuzzyRule(3, fuzzyAntecedentB_3, fuzzyConsequent_3); 860 | fuzzy->addFuzzyRule(fuzzyRule_3); 861 | 862 | // ############## Rule 4 863 | FuzzyRuleAntecedent *fuzzyAntecedentA_4 = new FuzzyRuleAntecedent(); 864 | fuzzyAntecedentA_4->joinWithAND(seco, frio); 865 | FuzzyRuleAntecedent *fuzzyAntecedentB_4 = new FuzzyRuleAntecedent(); 866 | fuzzyAntecedentB_4->joinWithAND(fuzzyAntecedentA_4, primavera); 867 | FuzzyRuleConsequent *fuzzyConsequent_4 = new FuzzyRuleConsequent(); 868 | fuzzyConsequent_4->addOutput(muyPoco); 869 | 870 | FuzzyRule *fuzzyRule_4 = new FuzzyRule(4, fuzzyAntecedentB_4, fuzzyConsequent_4); 871 | fuzzy->addFuzzyRule(fuzzyRule_4); 872 | 873 | // ############## Rule 5 874 | FuzzyRuleAntecedent *fuzzyAntecedentA_5 = new FuzzyRuleAntecedent(); 875 | fuzzyAntecedentA_5->joinWithAND(humedo, frio); 876 | FuzzyRuleAntecedent *fuzzyAntecedentB_5 = new FuzzyRuleAntecedent(); 877 | fuzzyAntecedentB_5->joinWithAND(fuzzyAntecedentA_5, verano); 878 | FuzzyRuleConsequent *fuzzyConsequent_5 = new FuzzyRuleConsequent(); 879 | fuzzyConsequent_5->addOutput(muyPoco); 880 | 881 | FuzzyRule *fuzzyRule_5 = new FuzzyRule(5, fuzzyAntecedentB_5, fuzzyConsequent_5); 882 | fuzzy->addFuzzyRule(fuzzyRule_5); 883 | 884 | // ############## Rule 6 885 | FuzzyRuleAntecedent *fuzzyAntecedentA_6 = new FuzzyRuleAntecedent(); 886 | fuzzyAntecedentA_6->joinWithAND(humedo, frio); 887 | FuzzyRuleAntecedent *fuzzyAntecedentB_6 = new FuzzyRuleAntecedent(); 888 | fuzzyAntecedentB_6->joinWithAND(fuzzyAntecedentA_6, otono); 889 | FuzzyRuleConsequent *fuzzyConsequent_6 = new FuzzyRuleConsequent(); 890 | fuzzyConsequent_6->addOutput(muyPoco); 891 | 892 | FuzzyRule *fuzzyRule_6 = new FuzzyRule(6, fuzzyAntecedentB_6, fuzzyConsequent_6); 893 | fuzzy->addFuzzyRule(fuzzyRule_6); 894 | 895 | // ############## Rule 7 896 | FuzzyRuleAntecedent *fuzzyAntecedentA_7 = new FuzzyRuleAntecedent(); 897 | fuzzyAntecedentA_7->joinWithAND(humedo, frio); 898 | FuzzyRuleAntecedent *fuzzyAntecedentB_7 = new FuzzyRuleAntecedent(); 899 | fuzzyAntecedentB_7->joinWithAND(fuzzyAntecedentA_7, invierno); 900 | FuzzyRuleConsequent *fuzzyConsequent_7 = new FuzzyRuleConsequent(); 901 | fuzzyConsequent_7->addOutput(muyPoco); 902 | 903 | FuzzyRule *fuzzyRule_7 = new FuzzyRule(7, fuzzyAntecedentB_7, fuzzyConsequent_7); 904 | fuzzy->addFuzzyRule(fuzzyRule_7); 905 | 906 | // ############## Rule 8 907 | FuzzyRuleAntecedent *fuzzyAntecedentA_8 = new FuzzyRuleAntecedent(); 908 | fuzzyAntecedentA_8->joinWithAND(humedo, frio); 909 | FuzzyRuleAntecedent *fuzzyAntecedentB_8 = new FuzzyRuleAntecedent(); 910 | fuzzyAntecedentB_8->joinWithAND(fuzzyAntecedentA_8, primavera); 911 | FuzzyRuleConsequent *fuzzyConsequent_8 = new FuzzyRuleConsequent(); 912 | fuzzyConsequent_8->addOutput(muyPoco); 913 | 914 | FuzzyRule *fuzzyRule_8 = new FuzzyRule(8, fuzzyAntecedentB_8, fuzzyConsequent_8); 915 | fuzzy->addFuzzyRule(fuzzyRule_8); 916 | 917 | // ############## Rule 9 918 | FuzzyRuleAntecedent *fuzzyAntecedentA_9 = new FuzzyRuleAntecedent(); 919 | fuzzyAntecedentA_9->joinWithAND(encharcado, frio); 920 | FuzzyRuleAntecedent *fuzzyAntecedentB_9 = new FuzzyRuleAntecedent(); 921 | fuzzyAntecedentB_9->joinWithAND(fuzzyAntecedentA_9, primavera); 922 | FuzzyRuleConsequent *fuzzyConsequent_9 = new FuzzyRuleConsequent(); 923 | fuzzyConsequent_9->addOutput(nada); 924 | 925 | FuzzyRule *fuzzyRule_9 = new FuzzyRule(9, fuzzyAntecedentB_9, fuzzyConsequent_9); 926 | fuzzy->addFuzzyRule(fuzzyRule_9); 927 | 928 | // ############## Rule 10 929 | FuzzyRuleAntecedent *fuzzyAntecedentA_10 = new FuzzyRuleAntecedent(); 930 | fuzzyAntecedentA_10->joinWithAND(encharcado, frio); 931 | FuzzyRuleAntecedent *fuzzyAntecedentB_10 = new FuzzyRuleAntecedent(); 932 | fuzzyAntecedentB_10->joinWithAND(fuzzyAntecedentA_10, otono); 933 | FuzzyRuleConsequent *fuzzyConsequent_10 = new FuzzyRuleConsequent(); 934 | fuzzyConsequent_10->addOutput(nada); 935 | 936 | FuzzyRule *fuzzyRule_10 = new FuzzyRule(10, fuzzyAntecedentB_10, fuzzyConsequent_10); 937 | fuzzy->addFuzzyRule(fuzzyRule_10); 938 | 939 | // ############## Rule 11 940 | FuzzyRuleAntecedent *fuzzyAntecedentA_11 = new FuzzyRuleAntecedent(); 941 | fuzzyAntecedentA_11->joinWithAND(encharcado, frio); 942 | FuzzyRuleAntecedent *fuzzyAntecedentB_11 = new FuzzyRuleAntecedent(); 943 | fuzzyAntecedentB_11->joinWithAND(fuzzyAntecedentA_11, invierno); 944 | FuzzyRuleConsequent *fuzzyConsequent_11 = new FuzzyRuleConsequent(); 945 | fuzzyConsequent_11->addOutput(nada); 946 | 947 | FuzzyRule *fuzzyRule_11 = new FuzzyRule(11, fuzzyAntecedentB_11, fuzzyConsequent_11); 948 | fuzzy->addFuzzyRule(fuzzyRule_11); 949 | 950 | // ############## Rule 12 951 | FuzzyRuleAntecedent *fuzzyAntecedentA_12 = new FuzzyRuleAntecedent(); 952 | fuzzyAntecedentA_12->joinWithAND(encharcado, frio); 953 | FuzzyRuleAntecedent *fuzzyAntecedentB_12 = new FuzzyRuleAntecedent(); 954 | fuzzyAntecedentB_12->joinWithAND(fuzzyAntecedentA_12, primavera); 955 | FuzzyRuleConsequent *fuzzyConsequent_12 = new FuzzyRuleConsequent(); 956 | fuzzyConsequent_12->addOutput(nada); 957 | 958 | FuzzyRule *fuzzyRule_12 = new FuzzyRule(12, fuzzyAntecedentB_12, fuzzyConsequent_12); 959 | fuzzy->addFuzzyRule(fuzzyRule_12); 960 | 961 | // ############## Rule 13 962 | FuzzyRuleAntecedent *fuzzyAntecedentA_13 = new FuzzyRuleAntecedent(); 963 | fuzzyAntecedentA_13->joinWithAND(seco, templado); 964 | FuzzyRuleAntecedent *fuzzyAntecedentB_13 = new FuzzyRuleAntecedent(); 965 | fuzzyAntecedentB_13->joinWithAND(fuzzyAntecedentA_13, verano); 966 | FuzzyRuleConsequent *fuzzyConsequent_13 = new FuzzyRuleConsequent(); 967 | fuzzyConsequent_13->addOutput(bastante); 968 | 969 | FuzzyRule *fuzzyRule_13 = new FuzzyRule(13, fuzzyAntecedentB_13, fuzzyConsequent_13); 970 | fuzzy->addFuzzyRule(fuzzyRule_13); 971 | 972 | // ############## Rule 14 973 | FuzzyRuleAntecedent *fuzzyAntecedentA_14 = new FuzzyRuleAntecedent(); 974 | fuzzyAntecedentA_14->joinWithAND(seco, templado); 975 | FuzzyRuleAntecedent *fuzzyAntecedentB_14 = new FuzzyRuleAntecedent(); 976 | fuzzyAntecedentB_14->joinWithAND(fuzzyAntecedentA_14, otono); 977 | FuzzyRuleConsequent *fuzzyConsequent_14 = new FuzzyRuleConsequent(); 978 | fuzzyConsequent_14->addOutput(medio); 979 | 980 | FuzzyRule *fuzzyRule_14 = new FuzzyRule(14, fuzzyAntecedentB_14, fuzzyConsequent_14); 981 | fuzzy->addFuzzyRule(fuzzyRule_14); 982 | 983 | // ############## Rule 15 984 | FuzzyRuleAntecedent *fuzzyAntecedentA_15 = new FuzzyRuleAntecedent(); 985 | fuzzyAntecedentA_15->joinWithAND(seco, templado); 986 | FuzzyRuleAntecedent *fuzzyAntecedentB_15 = new FuzzyRuleAntecedent(); 987 | fuzzyAntecedentB_15->joinWithAND(fuzzyAntecedentA_15, invierno); 988 | FuzzyRuleConsequent *fuzzyConsequent_15 = new FuzzyRuleConsequent(); 989 | fuzzyConsequent_15->addOutput(poco); 990 | 991 | FuzzyRule *fuzzyRule_15 = new FuzzyRule(15, fuzzyAntecedentB_15, fuzzyConsequent_15); 992 | fuzzy->addFuzzyRule(fuzzyRule_15); 993 | 994 | // ############## Rule 16 995 | FuzzyRuleAntecedent *fuzzyAntecedentA_16 = new FuzzyRuleAntecedent(); 996 | fuzzyAntecedentA_16->joinWithAND(seco, templado); 997 | FuzzyRuleAntecedent *fuzzyAntecedentB_16 = new FuzzyRuleAntecedent(); 998 | fuzzyAntecedentB_16->joinWithAND(fuzzyAntecedentA_16, primavera); 999 | FuzzyRuleConsequent *fuzzyConsequent_16 = new FuzzyRuleConsequent(); 1000 | fuzzyConsequent_16->addOutput(bastante); 1001 | 1002 | FuzzyRule *fuzzyRule_16 = new FuzzyRule(16, fuzzyAntecedentB_16, fuzzyConsequent_16); 1003 | fuzzy->addFuzzyRule(fuzzyRule_16); 1004 | 1005 | // ############## Rule 17 1006 | FuzzyRuleAntecedent *fuzzyAntecedentA_17 = new FuzzyRuleAntecedent(); 1007 | fuzzyAntecedentA_17->joinWithAND(humedo, templado); 1008 | FuzzyRuleAntecedent *fuzzyAntecedentB_17 = new FuzzyRuleAntecedent(); 1009 | fuzzyAntecedentB_17->joinWithAND(fuzzyAntecedentA_17, verano); 1010 | FuzzyRuleConsequent *fuzzyConsequent_17 = new FuzzyRuleConsequent(); 1011 | fuzzyConsequent_17->addOutput(medio); 1012 | 1013 | FuzzyRule *fuzzyRule_17 = new FuzzyRule(17, fuzzyAntecedentB_17, fuzzyConsequent_17); 1014 | fuzzy->addFuzzyRule(fuzzyRule_17); 1015 | 1016 | // ############## Rule 18 1017 | FuzzyRuleAntecedent *fuzzyAntecedentA_18 = new FuzzyRuleAntecedent(); 1018 | fuzzyAntecedentA_18->joinWithAND(humedo, templado); 1019 | FuzzyRuleAntecedent *fuzzyAntecedentB_18 = new FuzzyRuleAntecedent(); 1020 | fuzzyAntecedentB_18->joinWithAND(fuzzyAntecedentA_18, otono); 1021 | FuzzyRuleConsequent *fuzzyConsequent_18 = new FuzzyRuleConsequent(); 1022 | fuzzyConsequent_18->addOutput(poco); 1023 | 1024 | FuzzyRule *fuzzyRule_18 = new FuzzyRule(18, fuzzyAntecedentB_18, fuzzyConsequent_18); 1025 | fuzzy->addFuzzyRule(fuzzyRule_18); 1026 | 1027 | // ############## Rule 19 1028 | FuzzyRuleAntecedent *fuzzyAntecedentA_19 = new FuzzyRuleAntecedent(); 1029 | fuzzyAntecedentA_19->joinWithAND(humedo, templado); 1030 | FuzzyRuleAntecedent *fuzzyAntecedentB_19 = new FuzzyRuleAntecedent(); 1031 | fuzzyAntecedentB_19->joinWithAND(fuzzyAntecedentA_19, invierno); 1032 | FuzzyRuleConsequent *fuzzyConsequent_19 = new FuzzyRuleConsequent(); 1033 | fuzzyConsequent_19->addOutput(poco); 1034 | 1035 | FuzzyRule *fuzzyRule_19 = new FuzzyRule(19, fuzzyAntecedentB_19, fuzzyConsequent_19); 1036 | fuzzy->addFuzzyRule(fuzzyRule_19); 1037 | 1038 | // ############## Rule 20 1039 | FuzzyRuleAntecedent *fuzzyAntecedentA_20 = new FuzzyRuleAntecedent(); 1040 | fuzzyAntecedentA_20->joinWithAND(humedo, templado); 1041 | FuzzyRuleAntecedent *fuzzyAntecedentB_20 = new FuzzyRuleAntecedent(); 1042 | fuzzyAntecedentB_20->joinWithAND(fuzzyAntecedentA_20, primavera); 1043 | FuzzyRuleConsequent *fuzzyConsequent_20 = new FuzzyRuleConsequent(); 1044 | fuzzyConsequent_20->addOutput(medio); 1045 | 1046 | FuzzyRule *fuzzyRule_20 = new FuzzyRule(20, fuzzyAntecedentB_20, fuzzyConsequent_20); 1047 | fuzzy->addFuzzyRule(fuzzyRule_20); 1048 | 1049 | // ############## Rule 21 1050 | FuzzyRuleAntecedent *fuzzyAntecedentA_21 = new FuzzyRuleAntecedent(); 1051 | fuzzyAntecedentA_21->joinWithAND(encharcado, templado); 1052 | FuzzyRuleAntecedent *fuzzyAntecedentB_21 = new FuzzyRuleAntecedent(); 1053 | fuzzyAntecedentB_21->joinWithAND(fuzzyAntecedentA_21, primavera); 1054 | FuzzyRuleConsequent *fuzzyConsequent_21 = new FuzzyRuleConsequent(); 1055 | fuzzyConsequent_21->addOutput(muyPoco); 1056 | 1057 | FuzzyRule *fuzzyRule_21 = new FuzzyRule(21, fuzzyAntecedentB_21, fuzzyConsequent_21); 1058 | fuzzy->addFuzzyRule(fuzzyRule_21); 1059 | 1060 | // ############## Rule 22 1061 | FuzzyRuleAntecedent *fuzzyAntecedentA_22 = new FuzzyRuleAntecedent(); 1062 | fuzzyAntecedentA_22->joinWithAND(encharcado, templado); 1063 | FuzzyRuleAntecedent *fuzzyAntecedentB_22 = new FuzzyRuleAntecedent(); 1064 | fuzzyAntecedentB_22->joinWithAND(fuzzyAntecedentA_22, otono); 1065 | FuzzyRuleConsequent *fuzzyConsequent_22 = new FuzzyRuleConsequent(); 1066 | fuzzyConsequent_22->addOutput(nada); 1067 | 1068 | FuzzyRule *fuzzyRule_22 = new FuzzyRule(22, fuzzyAntecedentB_22, fuzzyConsequent_22); 1069 | fuzzy->addFuzzyRule(fuzzyRule_22); 1070 | 1071 | // ############## Rule 23 1072 | FuzzyRuleAntecedent *fuzzyAntecedentA_23 = new FuzzyRuleAntecedent(); 1073 | fuzzyAntecedentA_23->joinWithAND(encharcado, templado); 1074 | FuzzyRuleAntecedent *fuzzyAntecedentB_23 = new FuzzyRuleAntecedent(); 1075 | fuzzyAntecedentB_23->joinWithAND(fuzzyAntecedentA_23, invierno); 1076 | FuzzyRuleConsequent *fuzzyConsequent_23 = new FuzzyRuleConsequent(); 1077 | fuzzyConsequent_23->addOutput(nada); 1078 | 1079 | FuzzyRule *fuzzyRule_23 = new FuzzyRule(23, fuzzyAntecedentB_23, fuzzyConsequent_23); 1080 | fuzzy->addFuzzyRule(fuzzyRule_23); 1081 | 1082 | // ############## Rule 24 1083 | FuzzyRuleAntecedent *fuzzyAntecedentA_24 = new FuzzyRuleAntecedent(); 1084 | fuzzyAntecedentA_24->joinWithAND(encharcado, templado); 1085 | FuzzyRuleAntecedent *fuzzyAntecedentB_24 = new FuzzyRuleAntecedent(); 1086 | fuzzyAntecedentB_24->joinWithAND(fuzzyAntecedentA_24, primavera); 1087 | FuzzyRuleConsequent *fuzzyConsequent_24 = new FuzzyRuleConsequent(); 1088 | fuzzyConsequent_24->addOutput(muyPoco); 1089 | 1090 | FuzzyRule *fuzzyRule_24 = new FuzzyRule(24, fuzzyAntecedentB_24, fuzzyConsequent_24); 1091 | fuzzy->addFuzzyRule(fuzzyRule_24); 1092 | 1093 | // ############## Rule 25 1094 | FuzzyRuleAntecedent *fuzzyAntecedentA_25 = new FuzzyRuleAntecedent(); 1095 | fuzzyAntecedentA_25->joinWithAND(seco, calor); 1096 | FuzzyRuleAntecedent *fuzzyAntecedentB_25 = new FuzzyRuleAntecedent(); 1097 | fuzzyAntecedentB_25->joinWithAND(fuzzyAntecedentA_25, verano); 1098 | FuzzyRuleConsequent *fuzzyConsequent_25 = new FuzzyRuleConsequent(); 1099 | fuzzyConsequent_25->addOutput(mucho); 1100 | 1101 | FuzzyRule *fuzzyRule_25 = new FuzzyRule(25, fuzzyAntecedentB_25, fuzzyConsequent_25); 1102 | fuzzy->addFuzzyRule(fuzzyRule_25); 1103 | 1104 | // ############## Rule 26 1105 | FuzzyRuleAntecedent *fuzzyAntecedentA_26 = new FuzzyRuleAntecedent(); 1106 | fuzzyAntecedentA_26->joinWithAND(seco, calor); 1107 | FuzzyRuleAntecedent *fuzzyAntecedentB_26 = new FuzzyRuleAntecedent(); 1108 | fuzzyAntecedentB_26->joinWithAND(fuzzyAntecedentA_26, otono); 1109 | FuzzyRuleConsequent *fuzzyConsequent_26 = new FuzzyRuleConsequent(); 1110 | fuzzyConsequent_26->addOutput(medio); 1111 | 1112 | FuzzyRule *fuzzyRule_26 = new FuzzyRule(26, fuzzyAntecedentB_26, fuzzyConsequent_26); 1113 | fuzzy->addFuzzyRule(fuzzyRule_26); 1114 | 1115 | // ############## Rule 27 1116 | FuzzyRuleAntecedent *fuzzyAntecedentA_27 = new FuzzyRuleAntecedent(); 1117 | fuzzyAntecedentA_27->joinWithAND(seco, calor); 1118 | FuzzyRuleAntecedent *fuzzyAntecedentB_27 = new FuzzyRuleAntecedent(); 1119 | fuzzyAntecedentB_27->joinWithAND(fuzzyAntecedentA_27, invierno); 1120 | FuzzyRuleConsequent *fuzzyConsequent_27 = new FuzzyRuleConsequent(); 1121 | fuzzyConsequent_27->addOutput(medio); 1122 | 1123 | FuzzyRule *fuzzyRule_27 = new FuzzyRule(27, fuzzyAntecedentB_27, fuzzyConsequent_27); 1124 | fuzzy->addFuzzyRule(fuzzyRule_27); 1125 | 1126 | // ############## Rule 28 1127 | FuzzyRuleAntecedent *fuzzyAntecedentA_28 = new FuzzyRuleAntecedent(); 1128 | fuzzyAntecedentA_28->joinWithAND(seco, calor); 1129 | FuzzyRuleAntecedent *fuzzyAntecedentB_28 = new FuzzyRuleAntecedent(); 1130 | fuzzyAntecedentB_28->joinWithAND(fuzzyAntecedentA_28, primavera); 1131 | FuzzyRuleConsequent *fuzzyConsequent_28 = new FuzzyRuleConsequent(); 1132 | fuzzyConsequent_28->addOutput(mucho); 1133 | 1134 | FuzzyRule *fuzzyRule_28 = new FuzzyRule(28, fuzzyAntecedentB_28, fuzzyConsequent_28); 1135 | fuzzy->addFuzzyRule(fuzzyRule_28); 1136 | 1137 | // ############## Rule 29 1138 | FuzzyRuleAntecedent *fuzzyAntecedentA_29 = new FuzzyRuleAntecedent(); 1139 | fuzzyAntecedentA_29->joinWithAND(humedo, calor); 1140 | FuzzyRuleAntecedent *fuzzyAntecedentB_29 = new FuzzyRuleAntecedent(); 1141 | fuzzyAntecedentB_29->joinWithAND(fuzzyAntecedentA_29, verano); 1142 | FuzzyRuleConsequent *fuzzyConsequent_29 = new FuzzyRuleConsequent(); 1143 | fuzzyConsequent_29->addOutput(bastante); 1144 | 1145 | FuzzyRule *fuzzyRule_29 = new FuzzyRule(29, fuzzyAntecedentB_29, fuzzyConsequent_29); 1146 | fuzzy->addFuzzyRule(fuzzyRule_29); 1147 | 1148 | // ############## Rule 30 1149 | FuzzyRuleAntecedent *fuzzyAntecedentA_30 = new FuzzyRuleAntecedent(); 1150 | fuzzyAntecedentA_30->joinWithAND(humedo, calor); 1151 | FuzzyRuleAntecedent *fuzzyAntecedentB_30 = new FuzzyRuleAntecedent(); 1152 | fuzzyAntecedentB_30->joinWithAND(fuzzyAntecedentA_30, otono); 1153 | FuzzyRuleConsequent *fuzzyConsequent_30 = new FuzzyRuleConsequent(); 1154 | fuzzyConsequent_30->addOutput(bastante); 1155 | 1156 | FuzzyRule *fuzzyRule_30 = new FuzzyRule(30, fuzzyAntecedentB_30, fuzzyConsequent_30); 1157 | fuzzy->addFuzzyRule(fuzzyRule_30); 1158 | 1159 | // ############## Rule 31 1160 | FuzzyRuleAntecedent *fuzzyAntecedentA_31 = new FuzzyRuleAntecedent(); 1161 | fuzzyAntecedentA_31->joinWithAND(humedo, calor); 1162 | FuzzyRuleAntecedent *fuzzyAntecedentB_31 = new FuzzyRuleAntecedent(); 1163 | fuzzyAntecedentB_31->joinWithAND(fuzzyAntecedentA_31, invierno); 1164 | FuzzyRuleConsequent *fuzzyConsequent_31 = new FuzzyRuleConsequent(); 1165 | fuzzyConsequent_31->addOutput(bastante); 1166 | 1167 | FuzzyRule *fuzzyRule_31 = new FuzzyRule(31, fuzzyAntecedentB_31, fuzzyConsequent_31); 1168 | fuzzy->addFuzzyRule(fuzzyRule_31); 1169 | 1170 | // ############## Rule 32 1171 | FuzzyRuleAntecedent *fuzzyAntecedentA_32 = new FuzzyRuleAntecedent(); 1172 | fuzzyAntecedentA_32->joinWithAND(humedo, calor); 1173 | FuzzyRuleAntecedent *fuzzyAntecedentB_32 = new FuzzyRuleAntecedent(); 1174 | fuzzyAntecedentB_32->joinWithAND(fuzzyAntecedentA_32, primavera); 1175 | FuzzyRuleConsequent *fuzzyConsequent_32 = new FuzzyRuleConsequent(); 1176 | fuzzyConsequent_32->addOutput(medio); 1177 | 1178 | FuzzyRule *fuzzyRule_32 = new FuzzyRule(32, fuzzyAntecedentB_32, fuzzyConsequent_32); 1179 | fuzzy->addFuzzyRule(fuzzyRule_32); 1180 | 1181 | // ############## Rule 33 1182 | FuzzyRuleAntecedent *fuzzyAntecedentA_33 = new FuzzyRuleAntecedent(); 1183 | fuzzyAntecedentA_33->joinWithAND(encharcado, calor); 1184 | FuzzyRuleAntecedent *fuzzyAntecedentB_33 = new FuzzyRuleAntecedent(); 1185 | fuzzyAntecedentB_33->joinWithAND(fuzzyAntecedentA_33, verano); 1186 | FuzzyRuleConsequent *fuzzyConsequent_33 = new FuzzyRuleConsequent(); 1187 | fuzzyConsequent_33->addOutput(muyPoco); 1188 | 1189 | FuzzyRule *fuzzyRule_33 = new FuzzyRule(33, fuzzyAntecedentB_33, fuzzyConsequent_33); 1190 | fuzzy->addFuzzyRule(fuzzyRule_33); 1191 | 1192 | // ############## Rule 34 1193 | FuzzyRuleAntecedent *fuzzyAntecedentA_34 = new FuzzyRuleAntecedent(); 1194 | fuzzyAntecedentA_34->joinWithAND(encharcado, calor); 1195 | FuzzyRuleAntecedent *fuzzyAntecedentB_34 = new FuzzyRuleAntecedent(); 1196 | fuzzyAntecedentB_34->joinWithAND(fuzzyAntecedentA_34, otono); 1197 | FuzzyRuleConsequent *fuzzyConsequent_34 = new FuzzyRuleConsequent(); 1198 | fuzzyConsequent_34->addOutput(nada); 1199 | 1200 | FuzzyRule *fuzzyRule_34 = new FuzzyRule(34, fuzzyAntecedentB_34, fuzzyConsequent_34); 1201 | fuzzy->addFuzzyRule(fuzzyRule_34); 1202 | 1203 | // ############## Rule 35 1204 | FuzzyRuleAntecedent *fuzzyAntecedentA_35 = new FuzzyRuleAntecedent(); 1205 | fuzzyAntecedentA_35->joinWithAND(encharcado, calor); 1206 | FuzzyRuleAntecedent *fuzzyAntecedentB_35 = new FuzzyRuleAntecedent(); 1207 | fuzzyAntecedentB_35->joinWithAND(fuzzyAntecedentA_35, invierno); 1208 | FuzzyRuleConsequent *fuzzyConsequent_35 = new FuzzyRuleConsequent(); 1209 | fuzzyConsequent_35->addOutput(nada); 1210 | 1211 | FuzzyRule *fuzzyRule_35 = new FuzzyRule(35, fuzzyAntecedentB_35, fuzzyConsequent_35); 1212 | fuzzy->addFuzzyRule(fuzzyRule_35); 1213 | 1214 | // ############## Rule 36 1215 | FuzzyRuleAntecedent *fuzzyAntecedentA_36 = new FuzzyRuleAntecedent(); 1216 | fuzzyAntecedentA_36->joinWithAND(encharcado, calor); 1217 | FuzzyRuleAntecedent *fuzzyAntecedentB_36 = new FuzzyRuleAntecedent(); 1218 | fuzzyAntecedentB_36->joinWithAND(fuzzyAntecedentA_36, primavera); 1219 | FuzzyRuleConsequent *fuzzyConsequent_36 = new FuzzyRuleConsequent(); 1220 | fuzzyConsequent_36->addOutput(muyPoco); 1221 | 1222 | FuzzyRule *fuzzyRule_36 = new FuzzyRule(36, fuzzyAntecedentB_36, fuzzyConsequent_36); 1223 | fuzzy->addFuzzyRule(fuzzyRule_36); 1224 | 1225 | // TEST 01 1226 | fuzzy->setInput(1, 54.82); 1227 | fuzzy->setInput(2, 20); 1228 | fuzzy->setInput(3, 6); 1229 | 1230 | fuzzy->fuzzify(); 1231 | 1232 | EXPECT_FLOAT_EQ(7.5, fuzzy->defuzzify(1)); 1233 | 1234 | // TEST 02 1235 | fuzzy->setInput(1, 12.65); 1236 | fuzzy->setInput(2, 1.928); 1237 | fuzzy->setInput(3, 6); 1238 | 1239 | fuzzy->fuzzify(); 1240 | 1241 | EXPECT_FLOAT_EQ(2.4226191, fuzzy->defuzzify(1)); // 2.35 on original file 1242 | 1243 | // TEST 03 1244 | fuzzy->setInput(1, 25.9); 1245 | fuzzy->setInput(2, 8.55); 1246 | fuzzy->setInput(3, 6); 1247 | 1248 | fuzzy->fuzzify(); 1249 | 1250 | EXPECT_FLOAT_EQ(6.4175873, fuzzy->defuzzify(1)); // 6.21 on original file 1251 | 1252 | // TEST 04 1253 | fuzzy->setInput(1, 71.69); 1254 | fuzzy->setInput(2, 8.554); 1255 | fuzzy->setInput(3, 6); 1256 | 1257 | fuzzy->fuzzify(); 1258 | 1259 | EXPECT_FLOAT_EQ(4.2093439, fuzzy->defuzzify(1)); // 4.12 on original file 1260 | 1261 | // TEST 05 1262 | fuzzy->setInput(1, 71.69); 1263 | fuzzy->setInput(2, 27.83); 1264 | fuzzy->setInput(3, 9.036); 1265 | 1266 | fuzzy->fuzzify(); 1267 | 1268 | EXPECT_FLOAT_EQ(15.478251, fuzzy->defuzzify(1)); // 15.5 on original file 1269 | 1270 | // TEST 06 1271 | fuzzy->setInput(1, 16.27); 1272 | fuzzy->setInput(2, 27.83); 1273 | fuzzy->setInput(3, 9.036); 1274 | 1275 | fuzzy->fuzzify(); 1276 | 1277 | EXPECT_FLOAT_EQ(16.58123, fuzzy->defuzzify(1)); // 16.6 on original file 1278 | 1279 | // TEST 07 1280 | fuzzy->setInput(1, 82.53); 1281 | fuzzy->setInput(2, 27.83); 1282 | fuzzy->setInput(3, 10.63); 1283 | 1284 | fuzzy->fuzzify(); 1285 | 1286 | EXPECT_FLOAT_EQ(2.4555054, fuzzy->defuzzify(1)); // 2.38 on original file 1287 | 1288 | // TEST 08 1289 | fuzzy->setInput(1, 7.831); 1290 | fuzzy->setInput(2, 27.83); 1291 | fuzzy->setInput(3, 10.63); 1292 | 1293 | fuzzy->fuzzify(); 1294 | 1295 | EXPECT_FLOAT_EQ(22.5, fuzzy->defuzzify(1)); 1296 | 1297 | // TEST 09 1298 | fuzzy->setInput(1, 7.831); 1299 | fuzzy->setInput(2, 7.952); 1300 | fuzzy->setInput(3, 10.63); 1301 | 1302 | fuzzy->fuzzify(); 1303 | 1304 | EXPECT_FLOAT_EQ(5.0615907, fuzzy->defuzzify(1)); // 4.96 on original file 1305 | } 1306 | 1307 | TEST(Fuzzy, setInputAndFuzzifyAndDefuzzify09) 1308 | { 1309 | // Instantiating an object of library 1310 | Fuzzy *fuzzy = new Fuzzy(); 1311 | 1312 | FuzzyInput *shift; 1313 | FuzzyInput *distance; 1314 | 1315 | FuzzyOutput *steeringangle; 1316 | FuzzyOutput *runningspeed; 1317 | 1318 | FuzzyRuleAntecedent *ifShiftS_4AndDistanceD_0; 1319 | FuzzyRuleConsequent *thenSteeringangleAng_4AndRunningspeedSpeed_2; 1320 | FuzzyRule *fuzzyRule1; 1321 | 1322 | FuzzyRuleAntecedent *ifShiftS_4AndDistanceD_1; 1323 | FuzzyRuleConsequent *thenSteeringangleAng_4AndRunningspeedSpeed_1; 1324 | FuzzyRule *fuzzyRule2; 1325 | 1326 | FuzzyRuleAntecedent *ifShiftS_4AndDistanceD_2; 1327 | FuzzyRule *fuzzyRule3; 1328 | 1329 | FuzzyRuleAntecedent *ifShiftS_4AndDistanceD_3; 1330 | FuzzyRuleConsequent *thenSteeringangleAng_4AndRunningspeedSpeed_0; 1331 | FuzzyRule *fuzzyRule4; 1332 | 1333 | FuzzyRuleAntecedent *ifShiftS_4AndDistanceD_4; 1334 | FuzzyRule *fuzzyRule5; 1335 | 1336 | FuzzyRuleAntecedent *ifShiftS_3AndDistanceD_0; 1337 | FuzzyRuleConsequent *thenSteeringangleAng_3AndRunningspeedSpeed_3; 1338 | FuzzyRule *fuzzyRule6; 1339 | 1340 | FuzzyRuleAntecedent *ifShiftS_3AndDistanceD_1; 1341 | FuzzyRuleConsequent *thenSteeringangleAng_3AndRunningspeedSpeed_2; 1342 | FuzzyRule *fuzzyRule7; 1343 | 1344 | FuzzyRuleAntecedent *ifShiftS_3AndDistanceD_2; 1345 | FuzzyRuleConsequent *thenSteeringangleAng_3AndRunningspeedSpeed_1; 1346 | FuzzyRule *fuzzyRule8; 1347 | 1348 | FuzzyRuleAntecedent *ifShiftS_3AndDistanceD_3; 1349 | FuzzyRule *fuzzyRule9; 1350 | 1351 | FuzzyRuleAntecedent *ifShiftS_3AndDistanceD_4; 1352 | FuzzyRuleConsequent *thenSteeringangleAng_3AndRunningspeedSpeed_0; 1353 | FuzzyRule *fuzzyRule10; 1354 | 1355 | FuzzyRuleAntecedent *ifShiftS_2; 1356 | FuzzyRuleConsequent *thenSteeringangleAng_2AndRunningspeedSpeed_4; 1357 | FuzzyRule *fuzzyRule11; 1358 | 1359 | FuzzyRuleAntecedent *ifShiftS_1AndDistanceD_0; 1360 | FuzzyRuleConsequent *thenSteeringangleAng_1AndRunningspeedSpeed_3; 1361 | FuzzyRule *fuzzyRule12; 1362 | 1363 | FuzzyRuleAntecedent *ifShiftS_1AndDistanceD_1; 1364 | FuzzyRuleConsequent *thenSteeringangleAng_1AndRunningspeedSpeed_2; 1365 | FuzzyRule *fuzzyRule13; 1366 | 1367 | FuzzyRuleAntecedent *ifShiftS_1AndDistanceD_2; 1368 | FuzzyRuleConsequent *thenSteeringangleAng_1AndRunningspeedSpeed_1; 1369 | FuzzyRule *fuzzyRule14; 1370 | 1371 | FuzzyRuleAntecedent *ifShiftS_1AndDistanceD_3; 1372 | FuzzyRule *fuzzyRule15; 1373 | 1374 | FuzzyRuleAntecedent *ifShiftS_1AndDistanceD_4; 1375 | FuzzyRuleConsequent *thenSteeringangleAng_1AndRunningspeedSpeed_0; 1376 | FuzzyRule *fuzzyRule16; 1377 | 1378 | FuzzyRuleAntecedent *ifShiftS_0AndDistanceD_0; 1379 | FuzzyRuleConsequent *thenSteeringangleAng_0AndRunningspeedSpeed_2; 1380 | FuzzyRule *fuzzyRule17; 1381 | 1382 | FuzzyRuleAntecedent *ifShiftS_0AndDistanceD_1; 1383 | FuzzyRuleConsequent *thenSteeringangleAng_0AndRunningspeedSpeed_1; 1384 | FuzzyRule *fuzzyRule18; 1385 | 1386 | FuzzyRuleAntecedent *ifShiftS_0AndDistanceD_2; 1387 | FuzzyRule *fuzzyRule19; 1388 | 1389 | FuzzyRuleAntecedent *ifShiftS_0AndDistanceD_3; 1390 | FuzzyRuleConsequent *thenSteeringangleAng_0AndRunningspeedSpeed_0; 1391 | FuzzyRule *fuzzyRule20; 1392 | 1393 | FuzzyRuleAntecedent *ifShiftS_0AndDistanceD_4; 1394 | FuzzyRule *fuzzyRule21; 1395 | 1396 | // Fuzzy set 1397 | FuzzySet *s_0 = new FuzzySet(9, 21, 21, 33); //veri left 1398 | FuzzySet *s_1 = new FuzzySet(24, 31.5, 31.5, 39); //medium left 1399 | FuzzySet *s_2 = new FuzzySet(35, 39, 39, 43); //zero 1400 | FuzzySet *s_3 = new FuzzySet(39, 46.5, 46.5, 54); //medium right 1401 | FuzzySet *s_4 = new FuzzySet(45, 57, 57, 69); //very right 1402 | 1403 | FuzzySet *d_0 = new FuzzySet(0, 5, 5, 10); //farthest 1404 | FuzzySet *d_1 = new FuzzySet(5, 10, 10, 15); //far 1405 | FuzzySet *d_2 = new FuzzySet(10, 15, 15, 20); //middle 1406 | FuzzySet *d_3 = new FuzzySet(15, 25, 25, 35); //near 1407 | FuzzySet *d_4 = new FuzzySet(25, 42, 42, 59); //nearest 1408 | 1409 | FuzzySet *ang_0 = new FuzzySet(60, 70, 70, 80); //leftmost 1410 | FuzzySet *ang_1 = new FuzzySet(69, 79, 79, 89); //left 1411 | FuzzySet *ang_2 = new FuzzySet(88, 90, 90, 92); //middle 1412 | FuzzySet *ang_3 = new FuzzySet(91, 101, 101, 111); //right 1413 | FuzzySet *ang_4 = new FuzzySet(100, 110, 110, 120); // rightmost 1414 | 1415 | FuzzySet *speed_0 = new FuzzySet(50, 75, 75, 100); //very slow 1416 | FuzzySet *speed_1 = new FuzzySet(75, 110, 110, 145); //slow 1417 | FuzzySet *speed_2 = new FuzzySet(120, 150, 150, 180); //middle 1418 | FuzzySet *speed_3 = new FuzzySet(155, 190, 190, 225); //fast 1419 | FuzzySet *speed_4 = new FuzzySet(200, 225, 225, 250); //veryfast 1420 | 1421 | // Fuzzy input 1422 | shift = new FuzzyInput(1); 1423 | shift->addFuzzySet(s_0); 1424 | shift->addFuzzySet(s_1); 1425 | shift->addFuzzySet(s_2); 1426 | shift->addFuzzySet(s_3); 1427 | shift->addFuzzySet(s_4); 1428 | fuzzy->addFuzzyInput(shift); 1429 | 1430 | distance = new FuzzyInput(2); 1431 | distance->addFuzzySet(d_0); 1432 | distance->addFuzzySet(d_1); 1433 | distance->addFuzzySet(d_2); 1434 | distance->addFuzzySet(d_3); 1435 | distance->addFuzzySet(d_4); 1436 | fuzzy->addFuzzyInput(distance); 1437 | 1438 | // Fuzzy output 1439 | steeringangle = new FuzzyOutput(1); 1440 | steeringangle->addFuzzySet(ang_0); 1441 | steeringangle->addFuzzySet(ang_1); 1442 | steeringangle->addFuzzySet(ang_2); 1443 | steeringangle->addFuzzySet(ang_3); 1444 | steeringangle->addFuzzySet(ang_4); 1445 | fuzzy->addFuzzyOutput(steeringangle); 1446 | 1447 | runningspeed = new FuzzyOutput(2); 1448 | runningspeed->addFuzzySet(speed_0); 1449 | runningspeed->addFuzzySet(speed_1); 1450 | runningspeed->addFuzzySet(speed_2); 1451 | runningspeed->addFuzzySet(speed_3); 1452 | fuzzy->addFuzzyOutput(runningspeed); 1453 | 1454 | // Fuzzy rule 1455 | ifShiftS_4AndDistanceD_0 = new FuzzyRuleAntecedent(); 1456 | ifShiftS_4AndDistanceD_0->joinWithAND(s_4, d_0); 1457 | thenSteeringangleAng_4AndRunningspeedSpeed_2 = new FuzzyRuleConsequent(); 1458 | thenSteeringangleAng_4AndRunningspeedSpeed_2->addOutput(ang_4); 1459 | thenSteeringangleAng_4AndRunningspeedSpeed_2->addOutput(speed_2); 1460 | fuzzyRule1 = new FuzzyRule(1, ifShiftS_4AndDistanceD_0, thenSteeringangleAng_4AndRunningspeedSpeed_2); 1461 | fuzzy->addFuzzyRule(fuzzyRule1); 1462 | 1463 | ifShiftS_4AndDistanceD_1 = new FuzzyRuleAntecedent(); 1464 | ifShiftS_4AndDistanceD_1->joinWithAND(s_4, d_1); 1465 | thenSteeringangleAng_4AndRunningspeedSpeed_1 = new FuzzyRuleConsequent(); 1466 | thenSteeringangleAng_4AndRunningspeedSpeed_1->addOutput(ang_4); 1467 | thenSteeringangleAng_4AndRunningspeedSpeed_1->addOutput(speed_1); 1468 | fuzzyRule2 = new FuzzyRule(2, ifShiftS_4AndDistanceD_1, thenSteeringangleAng_4AndRunningspeedSpeed_1); 1469 | fuzzy->addFuzzyRule(fuzzyRule2); 1470 | 1471 | ifShiftS_4AndDistanceD_2 = new FuzzyRuleAntecedent(); 1472 | ifShiftS_4AndDistanceD_2->joinWithAND(s_4, d_2); 1473 | // FuzzyRuleConsequent* thenSteeringangleAng_4AndRunningspeedSpeed_1 = new FuzzyRuleConsequent(); 1474 | // thenSteeringangleAng_4AndRunningspeedSpeed_1->addOutput(ang_4); 1475 | // thenSteeringangleAng_4AndRunningspeedSpeed_1->addOutput(speed_1); 1476 | fuzzyRule3 = new FuzzyRule(3, ifShiftS_4AndDistanceD_2, thenSteeringangleAng_4AndRunningspeedSpeed_1); 1477 | fuzzy->addFuzzyRule(fuzzyRule3); 1478 | 1479 | ifShiftS_4AndDistanceD_3 = new FuzzyRuleAntecedent(); 1480 | ifShiftS_4AndDistanceD_3->joinWithAND(s_4, d_3); 1481 | thenSteeringangleAng_4AndRunningspeedSpeed_0 = new FuzzyRuleConsequent(); 1482 | thenSteeringangleAng_4AndRunningspeedSpeed_0->addOutput(ang_4); 1483 | thenSteeringangleAng_4AndRunningspeedSpeed_0->addOutput(speed_0); 1484 | fuzzyRule4 = new FuzzyRule(4, ifShiftS_4AndDistanceD_3, thenSteeringangleAng_4AndRunningspeedSpeed_0); 1485 | fuzzy->addFuzzyRule(fuzzyRule4); 1486 | 1487 | ifShiftS_4AndDistanceD_4 = new FuzzyRuleAntecedent(); 1488 | ifShiftS_4AndDistanceD_4->joinWithAND(s_4, d_4); 1489 | // FuzzyRuleConsequent* thenSteeringangleAng_4AndRunningspeedSpeed_0 = new FuzzyRuleConsequent(); 1490 | // thenSteeringangleAng_4AndRunningspeedSpeed_0->addOutput(ang_4); 1491 | // thenSteeringangleAng_4AndRunningspeedSpeed_0->addOutput(speed_0); 1492 | fuzzyRule5 = new FuzzyRule(5, ifShiftS_4AndDistanceD_4, thenSteeringangleAng_4AndRunningspeedSpeed_0); 1493 | fuzzy->addFuzzyRule(fuzzyRule5); 1494 | 1495 | ifShiftS_3AndDistanceD_0 = new FuzzyRuleAntecedent(); 1496 | ifShiftS_3AndDistanceD_0->joinWithAND(s_3, d_0); 1497 | thenSteeringangleAng_3AndRunningspeedSpeed_3 = new FuzzyRuleConsequent(); 1498 | thenSteeringangleAng_3AndRunningspeedSpeed_3->addOutput(ang_3); 1499 | thenSteeringangleAng_3AndRunningspeedSpeed_3->addOutput(speed_3); 1500 | fuzzyRule6 = new FuzzyRule(6, ifShiftS_3AndDistanceD_0, thenSteeringangleAng_3AndRunningspeedSpeed_3); 1501 | fuzzy->addFuzzyRule(fuzzyRule6); 1502 | 1503 | ifShiftS_3AndDistanceD_1 = new FuzzyRuleAntecedent(); 1504 | ifShiftS_3AndDistanceD_1->joinWithAND(s_3, d_1); 1505 | thenSteeringangleAng_3AndRunningspeedSpeed_2 = new FuzzyRuleConsequent(); 1506 | thenSteeringangleAng_3AndRunningspeedSpeed_2->addOutput(ang_3); 1507 | thenSteeringangleAng_3AndRunningspeedSpeed_2->addOutput(speed_2); 1508 | fuzzyRule7 = new FuzzyRule(7, ifShiftS_3AndDistanceD_1, thenSteeringangleAng_3AndRunningspeedSpeed_2); 1509 | fuzzy->addFuzzyRule(fuzzyRule7); 1510 | 1511 | ifShiftS_3AndDistanceD_2 = new FuzzyRuleAntecedent(); 1512 | ifShiftS_3AndDistanceD_2->joinWithAND(s_3, d_2); 1513 | thenSteeringangleAng_3AndRunningspeedSpeed_1 = new FuzzyRuleConsequent(); 1514 | thenSteeringangleAng_3AndRunningspeedSpeed_1->addOutput(ang_3); 1515 | thenSteeringangleAng_3AndRunningspeedSpeed_1->addOutput(speed_1); 1516 | fuzzyRule8 = new FuzzyRule(8, ifShiftS_3AndDistanceD_2, thenSteeringangleAng_3AndRunningspeedSpeed_1); 1517 | fuzzy->addFuzzyRule(fuzzyRule8); 1518 | 1519 | ifShiftS_3AndDistanceD_3 = new FuzzyRuleAntecedent(); 1520 | ifShiftS_3AndDistanceD_3->joinWithAND(s_3, d_3); 1521 | // FuzzyRuleConsequent* thenSteeringangleAng_3AndRunningspeedSpeed_1 = new FuzzyRuleConsequent(); 1522 | // thenSteeringangleAng_3AndRunningspeedSpeed_1->addOutput(ang_3); 1523 | // thenSteeringangleAng_3AndRunningspeedSpeed_1->addOutput(speed_1); 1524 | fuzzyRule9 = new FuzzyRule(9, ifShiftS_3AndDistanceD_3, thenSteeringangleAng_3AndRunningspeedSpeed_1); 1525 | fuzzy->addFuzzyRule(fuzzyRule9); 1526 | 1527 | ifShiftS_3AndDistanceD_4 = new FuzzyRuleAntecedent(); 1528 | ifShiftS_3AndDistanceD_4->joinWithAND(s_3, d_4); 1529 | thenSteeringangleAng_3AndRunningspeedSpeed_0 = new FuzzyRuleConsequent(); 1530 | thenSteeringangleAng_3AndRunningspeedSpeed_0->addOutput(ang_3); 1531 | thenSteeringangleAng_3AndRunningspeedSpeed_0->addOutput(speed_0); 1532 | fuzzyRule10 = new FuzzyRule(10, ifShiftS_3AndDistanceD_4, thenSteeringangleAng_3AndRunningspeedSpeed_0); 1533 | fuzzy->addFuzzyRule(fuzzyRule10); 1534 | 1535 | ifShiftS_2 = new FuzzyRuleAntecedent(); 1536 | ifShiftS_2->joinSingle(s_2); 1537 | thenSteeringangleAng_2AndRunningspeedSpeed_4 = new FuzzyRuleConsequent(); 1538 | thenSteeringangleAng_2AndRunningspeedSpeed_4->addOutput(ang_2); 1539 | thenSteeringangleAng_2AndRunningspeedSpeed_4->addOutput(speed_4); 1540 | fuzzyRule11 = new FuzzyRule(11, ifShiftS_2, thenSteeringangleAng_2AndRunningspeedSpeed_4); 1541 | fuzzy->addFuzzyRule(fuzzyRule11); 1542 | 1543 | ifShiftS_1AndDistanceD_0 = new FuzzyRuleAntecedent(); 1544 | ifShiftS_1AndDistanceD_0->joinWithAND(s_1, d_0); 1545 | thenSteeringangleAng_1AndRunningspeedSpeed_3 = new FuzzyRuleConsequent(); 1546 | thenSteeringangleAng_1AndRunningspeedSpeed_3->addOutput(ang_1); 1547 | thenSteeringangleAng_1AndRunningspeedSpeed_3->addOutput(speed_3); 1548 | fuzzyRule12 = new FuzzyRule(12, ifShiftS_1AndDistanceD_0, thenSteeringangleAng_1AndRunningspeedSpeed_3); 1549 | fuzzy->addFuzzyRule(fuzzyRule12); 1550 | 1551 | ifShiftS_1AndDistanceD_1 = new FuzzyRuleAntecedent(); 1552 | ifShiftS_1AndDistanceD_1->joinWithAND(s_1, d_1); 1553 | thenSteeringangleAng_1AndRunningspeedSpeed_2 = new FuzzyRuleConsequent(); 1554 | thenSteeringangleAng_1AndRunningspeedSpeed_2->addOutput(ang_1); 1555 | thenSteeringangleAng_1AndRunningspeedSpeed_2->addOutput(speed_2); 1556 | fuzzyRule13 = new FuzzyRule(13, ifShiftS_1AndDistanceD_1, thenSteeringangleAng_1AndRunningspeedSpeed_2); 1557 | fuzzy->addFuzzyRule(fuzzyRule13); 1558 | 1559 | ifShiftS_1AndDistanceD_2 = new FuzzyRuleAntecedent(); 1560 | ifShiftS_1AndDistanceD_2->joinWithAND(s_1, d_2); 1561 | thenSteeringangleAng_1AndRunningspeedSpeed_1 = new FuzzyRuleConsequent(); 1562 | thenSteeringangleAng_1AndRunningspeedSpeed_1->addOutput(ang_1); 1563 | thenSteeringangleAng_1AndRunningspeedSpeed_1->addOutput(speed_1); 1564 | fuzzyRule14 = new FuzzyRule(14, ifShiftS_1AndDistanceD_2, thenSteeringangleAng_1AndRunningspeedSpeed_1); 1565 | fuzzy->addFuzzyRule(fuzzyRule14); 1566 | 1567 | ifShiftS_1AndDistanceD_3 = new FuzzyRuleAntecedent(); 1568 | ifShiftS_1AndDistanceD_3->joinWithAND(s_1, d_3); 1569 | // FuzzyRuleConsequent* thenSteeringangleAng_1AndRunningspeedSpeed_1 = new FuzzyRuleConsequent(); 1570 | // thenSteeringangleAng_1AndRunningspeedSpeed_1->addOutput(ang_1); 1571 | // thenSteeringangleAng_1AndRunningspeedSpeed_1->addOutput(speed_1); 1572 | fuzzyRule15 = new FuzzyRule(15, ifShiftS_1AndDistanceD_3, thenSteeringangleAng_1AndRunningspeedSpeed_1); 1573 | fuzzy->addFuzzyRule(fuzzyRule15); 1574 | 1575 | ifShiftS_1AndDistanceD_4 = new FuzzyRuleAntecedent(); 1576 | ifShiftS_1AndDistanceD_4->joinWithAND(s_1, d_4); 1577 | thenSteeringangleAng_1AndRunningspeedSpeed_0 = new FuzzyRuleConsequent(); 1578 | thenSteeringangleAng_1AndRunningspeedSpeed_0->addOutput(ang_1); 1579 | thenSteeringangleAng_1AndRunningspeedSpeed_0->addOutput(speed_0); 1580 | fuzzyRule16 = new FuzzyRule(16, ifShiftS_1AndDistanceD_4, thenSteeringangleAng_1AndRunningspeedSpeed_0); 1581 | fuzzy->addFuzzyRule(fuzzyRule16); 1582 | 1583 | ifShiftS_0AndDistanceD_0 = new FuzzyRuleAntecedent(); 1584 | ifShiftS_0AndDistanceD_0->joinWithAND(s_0, d_0); 1585 | thenSteeringangleAng_0AndRunningspeedSpeed_2 = new FuzzyRuleConsequent(); 1586 | thenSteeringangleAng_0AndRunningspeedSpeed_2->addOutput(ang_0); 1587 | thenSteeringangleAng_0AndRunningspeedSpeed_2->addOutput(speed_2); 1588 | fuzzyRule17 = new FuzzyRule(17, ifShiftS_0AndDistanceD_0, thenSteeringangleAng_0AndRunningspeedSpeed_2); 1589 | fuzzy->addFuzzyRule(fuzzyRule17); 1590 | 1591 | ifShiftS_0AndDistanceD_1 = new FuzzyRuleAntecedent(); 1592 | ifShiftS_0AndDistanceD_1->joinWithAND(s_0, d_1); 1593 | thenSteeringangleAng_0AndRunningspeedSpeed_1 = new FuzzyRuleConsequent(); 1594 | thenSteeringangleAng_0AndRunningspeedSpeed_1->addOutput(ang_0); 1595 | thenSteeringangleAng_0AndRunningspeedSpeed_1->addOutput(speed_1); 1596 | fuzzyRule18 = new FuzzyRule(18, ifShiftS_0AndDistanceD_1, thenSteeringangleAng_0AndRunningspeedSpeed_1); 1597 | fuzzy->addFuzzyRule(fuzzyRule18); 1598 | 1599 | ifShiftS_0AndDistanceD_2 = new FuzzyRuleAntecedent(); 1600 | ifShiftS_0AndDistanceD_2->joinWithAND(s_0, d_2); 1601 | // FuzzyRuleConsequent* thenSteeringangleAng_0AndRunningspeedSpeed_1 = new FuzzyRuleConsequent(); 1602 | // thenSteeringangleAng_0AndRunningspeedSpeed_1->addOutput(ang_0); 1603 | // thenSteeringangleAng_0AndRunningspeedSpeed_1->addOutput(speed_1); 1604 | fuzzyRule19 = new FuzzyRule(19, ifShiftS_0AndDistanceD_2, thenSteeringangleAng_0AndRunningspeedSpeed_1); 1605 | fuzzy->addFuzzyRule(fuzzyRule19); 1606 | 1607 | ifShiftS_0AndDistanceD_3 = new FuzzyRuleAntecedent(); 1608 | ifShiftS_0AndDistanceD_3->joinWithAND(s_0, d_3); 1609 | thenSteeringangleAng_0AndRunningspeedSpeed_0 = new FuzzyRuleConsequent(); 1610 | thenSteeringangleAng_0AndRunningspeedSpeed_0->addOutput(ang_0); 1611 | thenSteeringangleAng_0AndRunningspeedSpeed_0->addOutput(speed_0); 1612 | fuzzyRule20 = new FuzzyRule(20, ifShiftS_0AndDistanceD_3, thenSteeringangleAng_0AndRunningspeedSpeed_0); 1613 | fuzzy->addFuzzyRule(fuzzyRule20); 1614 | 1615 | ifShiftS_0AndDistanceD_4 = new FuzzyRuleAntecedent(); 1616 | ifShiftS_0AndDistanceD_4->joinWithAND(s_0, d_4); 1617 | // FuzzyRuleConsequent* thenSteeringangleAng_0AndRunningspeedSpeed_0 = new FuzzyRuleConsequent(); 1618 | // thenSteeringangleAng_0AndRunningspeedSpeed_0->addOutput(ang_0); 1619 | // thenSteeringangleAng_0AndRunningspeedSpeed_0->addOutput(speed_0); 1620 | fuzzyRule21 = new FuzzyRule(21, ifShiftS_0AndDistanceD_4, thenSteeringangleAng_0AndRunningspeedSpeed_0); 1621 | fuzzy->addFuzzyRule(fuzzyRule21); 1622 | 1623 | float target_x = 21.88; // key in the digital value 1624 | float target_y = 32; 1625 | 1626 | // target_x and target_y are the inputs 1627 | fuzzy->setInput(1, target_x); // shift 1628 | fuzzy->setInput(2, target_y); // deistance 1629 | 1630 | fuzzy->fuzzify(); // Executing the fuzzification 1631 | 1632 | float output1 = fuzzy->defuzzify(1); // steering angle 1633 | float output2 = fuzzy->defuzzify(2); // running speed 1634 | 1635 | ASSERT_NEAR(70.0, output1, 0.01); 1636 | ASSERT_NEAR(75.0, output2, 0.01); 1637 | } 1638 | 1639 | // ##### MAIN 1640 | 1641 | int main(int argc, char **argv) 1642 | { 1643 | testing::InitGoogleTest(&argc, argv); 1644 | return RUN_ALL_TESTS(); 1645 | } 1646 | --------------------------------------------------------------------------------