Fuzzy libray for embedded targets developed by zerokol. Read more on: http://zerokol.com/product/51e93616e84c5571b7000018/2/en edit by Bruno Alfano - corrected deallocation of FuzzyOutput
Fuzzy library by Zerokol. Read more on: http://zerokol.com/product/51e93616e84c5571b7000018/2/en
edit by Bruno Alfano - corrected deallocation bug for FuzzyOutput
FuzzyRuleAntecedent.cpp@2:460b409e26e8, 2015-06-24 (annotated)
- Committer:
- astaff15
- Date:
- Wed Jun 24 15:08:13 2015 +0000
- Revision:
- 2:460b409e26e8
- Parent:
- 0:66cd67db4f1b
Corrected FuzzyOutput destructor bug
Who changed what in which revision?
User | Revision | Line number | New contents of line |
---|---|---|---|
astaff15 | 0:66cd67db4f1b | 1 | /* |
astaff15 | 0:66cd67db4f1b | 2 | * Robotic Research Group (RRG) |
astaff15 | 0:66cd67db4f1b | 3 | * State University of Piaui (UESPI), Brazil - Piauí - Teresina |
astaff15 | 0:66cd67db4f1b | 4 | * |
astaff15 | 0:66cd67db4f1b | 5 | * FuzzyRuleAntecedent.cpp |
astaff15 | 0:66cd67db4f1b | 6 | * |
astaff15 | 0:66cd67db4f1b | 7 | * Author: Msc. Marvin Lemos <marvinlemos@gmail.com> |
astaff15 | 0:66cd67db4f1b | 8 | * AJ Alves <aj.alves@zerokol.com> |
astaff15 | 0:66cd67db4f1b | 9 | * Co authors: Douglas S. Kridi <douglaskridi@gmail.com> |
astaff15 | 0:66cd67db4f1b | 10 | * Kannya Leal <kannyal@hotmail.com> |
astaff15 | 0:66cd67db4f1b | 11 | */ |
astaff15 | 0:66cd67db4f1b | 12 | #include "FuzzyRuleAntecedent.h" |
astaff15 | 0:66cd67db4f1b | 13 | |
astaff15 | 0:66cd67db4f1b | 14 | // CONSTRUTORES |
astaff15 | 0:66cd67db4f1b | 15 | FuzzyRuleAntecedent::FuzzyRuleAntecedent(){ |
astaff15 | 0:66cd67db4f1b | 16 | this->op = 0; |
astaff15 | 0:66cd67db4f1b | 17 | this->mode = 0; |
astaff15 | 0:66cd67db4f1b | 18 | this->fuzzySet1 = NULL; |
astaff15 | 0:66cd67db4f1b | 19 | this->fuzzySet2 = NULL; |
astaff15 | 0:66cd67db4f1b | 20 | this->fuzzyRuleAntecedent1 = NULL; |
astaff15 | 0:66cd67db4f1b | 21 | this->fuzzyRuleAntecedent2 = NULL; |
astaff15 | 0:66cd67db4f1b | 22 | } |
astaff15 | 0:66cd67db4f1b | 23 | |
astaff15 | 0:66cd67db4f1b | 24 | // MÉTODOS PÚBLICOS |
astaff15 | 0:66cd67db4f1b | 25 | bool FuzzyRuleAntecedent::joinSingle(FuzzySet* fuzzySet){ |
astaff15 | 0:66cd67db4f1b | 26 | if(fuzzySet){ |
astaff15 | 0:66cd67db4f1b | 27 | this->mode = MODE_FS; |
astaff15 | 0:66cd67db4f1b | 28 | this->fuzzySet1 = fuzzySet; |
astaff15 | 0:66cd67db4f1b | 29 | return true; |
astaff15 | 0:66cd67db4f1b | 30 | } |
astaff15 | 0:66cd67db4f1b | 31 | return false; |
astaff15 | 0:66cd67db4f1b | 32 | } |
astaff15 | 0:66cd67db4f1b | 33 | |
astaff15 | 0:66cd67db4f1b | 34 | bool FuzzyRuleAntecedent::joinWithAND(FuzzySet* fuzzySet1, FuzzySet* fuzzySet2){ |
astaff15 | 0:66cd67db4f1b | 35 | if(fuzzySet1 != NULL and fuzzySet2 != NULL){ |
astaff15 | 0:66cd67db4f1b | 36 | this->op = OP_AND; |
astaff15 | 0:66cd67db4f1b | 37 | this->mode = MODE_FS_FS; |
astaff15 | 0:66cd67db4f1b | 38 | this->fuzzySet1 = fuzzySet1; |
astaff15 | 0:66cd67db4f1b | 39 | this->fuzzySet2 = fuzzySet2; |
astaff15 | 0:66cd67db4f1b | 40 | return true; |
astaff15 | 0:66cd67db4f1b | 41 | } |
astaff15 | 0:66cd67db4f1b | 42 | return false; |
astaff15 | 0:66cd67db4f1b | 43 | } |
astaff15 | 0:66cd67db4f1b | 44 | |
astaff15 | 0:66cd67db4f1b | 45 | bool FuzzyRuleAntecedent::joinWithOR(FuzzySet* fuzzySet1, FuzzySet* fuzzySet2){ |
astaff15 | 0:66cd67db4f1b | 46 | if(fuzzySet1 != NULL and fuzzySet2 != NULL){ |
astaff15 | 0:66cd67db4f1b | 47 | this->op = OP_OR; |
astaff15 | 0:66cd67db4f1b | 48 | this->mode = MODE_FS_FS; |
astaff15 | 0:66cd67db4f1b | 49 | this->fuzzySet1 = fuzzySet1; |
astaff15 | 0:66cd67db4f1b | 50 | this->fuzzySet2 = fuzzySet2; |
astaff15 | 0:66cd67db4f1b | 51 | return true; |
astaff15 | 0:66cd67db4f1b | 52 | } |
astaff15 | 0:66cd67db4f1b | 53 | return false; |
astaff15 | 0:66cd67db4f1b | 54 | } |
astaff15 | 0:66cd67db4f1b | 55 | |
astaff15 | 0:66cd67db4f1b | 56 | bool FuzzyRuleAntecedent::joinWithAND(FuzzySet* fuzzySet, FuzzyRuleAntecedent* fuzzyRuleAntecedent){ |
astaff15 | 0:66cd67db4f1b | 57 | if(fuzzySet != NULL and fuzzyRuleAntecedent != NULL){ |
astaff15 | 0:66cd67db4f1b | 58 | this->op = OP_AND; |
astaff15 | 0:66cd67db4f1b | 59 | this->mode = MODE_FS_FRA; |
astaff15 | 0:66cd67db4f1b | 60 | this->fuzzySet1 = fuzzySet; |
astaff15 | 0:66cd67db4f1b | 61 | this->fuzzyRuleAntecedent1 = fuzzyRuleAntecedent; |
astaff15 | 0:66cd67db4f1b | 62 | return true; |
astaff15 | 0:66cd67db4f1b | 63 | } |
astaff15 | 0:66cd67db4f1b | 64 | return false; |
astaff15 | 0:66cd67db4f1b | 65 | } |
astaff15 | 0:66cd67db4f1b | 66 | |
astaff15 | 0:66cd67db4f1b | 67 | bool FuzzyRuleAntecedent::joinWithAND(FuzzyRuleAntecedent* fuzzyRuleAntecedent, FuzzySet* fuzzySet){ |
astaff15 | 0:66cd67db4f1b | 68 | if(fuzzySet != NULL and fuzzyRuleAntecedent != NULL){ |
astaff15 | 0:66cd67db4f1b | 69 | this->op = OP_AND; |
astaff15 | 0:66cd67db4f1b | 70 | this->mode = MODE_FS_FRA; |
astaff15 | 0:66cd67db4f1b | 71 | this->fuzzySet1 = fuzzySet; |
astaff15 | 0:66cd67db4f1b | 72 | this->fuzzyRuleAntecedent1 = fuzzyRuleAntecedent; |
astaff15 | 0:66cd67db4f1b | 73 | return true; |
astaff15 | 0:66cd67db4f1b | 74 | } |
astaff15 | 0:66cd67db4f1b | 75 | return false; |
astaff15 | 0:66cd67db4f1b | 76 | } |
astaff15 | 0:66cd67db4f1b | 77 | |
astaff15 | 0:66cd67db4f1b | 78 | bool FuzzyRuleAntecedent::joinWithOR(FuzzySet* fuzzySet, FuzzyRuleAntecedent* fuzzyRuleAntecedent){ |
astaff15 | 0:66cd67db4f1b | 79 | if(fuzzySet != NULL and fuzzyRuleAntecedent != NULL){ |
astaff15 | 0:66cd67db4f1b | 80 | this->op = OP_OR; |
astaff15 | 0:66cd67db4f1b | 81 | this->mode = MODE_FS_FRA; |
astaff15 | 0:66cd67db4f1b | 82 | this->fuzzySet1 = fuzzySet; |
astaff15 | 0:66cd67db4f1b | 83 | this->fuzzyRuleAntecedent1 = fuzzyRuleAntecedent; |
astaff15 | 0:66cd67db4f1b | 84 | return true; |
astaff15 | 0:66cd67db4f1b | 85 | } |
astaff15 | 0:66cd67db4f1b | 86 | return false; |
astaff15 | 0:66cd67db4f1b | 87 | } |
astaff15 | 0:66cd67db4f1b | 88 | |
astaff15 | 0:66cd67db4f1b | 89 | bool FuzzyRuleAntecedent::joinWithOR(FuzzyRuleAntecedent* fuzzyRuleAntecedent, FuzzySet* fuzzySet){ |
astaff15 | 0:66cd67db4f1b | 90 | if(fuzzySet != NULL and fuzzyRuleAntecedent != NULL){ |
astaff15 | 0:66cd67db4f1b | 91 | this->op = OP_OR; |
astaff15 | 0:66cd67db4f1b | 92 | this->mode = MODE_FS_FRA; |
astaff15 | 0:66cd67db4f1b | 93 | this->fuzzySet1 = fuzzySet; |
astaff15 | 0:66cd67db4f1b | 94 | this->fuzzyRuleAntecedent1 = fuzzyRuleAntecedent; |
astaff15 | 0:66cd67db4f1b | 95 | return true; |
astaff15 | 0:66cd67db4f1b | 96 | } |
astaff15 | 0:66cd67db4f1b | 97 | return false; |
astaff15 | 0:66cd67db4f1b | 98 | } |
astaff15 | 0:66cd67db4f1b | 99 | |
astaff15 | 0:66cd67db4f1b | 100 | bool FuzzyRuleAntecedent::joinWithAND(FuzzyRuleAntecedent* fuzzyRuleAntecedent1, FuzzyRuleAntecedent* fuzzyRuleAntecedent2){ |
astaff15 | 0:66cd67db4f1b | 101 | if(fuzzyRuleAntecedent1 != NULL and fuzzyRuleAntecedent2 != NULL){ |
astaff15 | 0:66cd67db4f1b | 102 | this->op = OP_AND; |
astaff15 | 0:66cd67db4f1b | 103 | this->mode = MODE_FRA_FRA; |
astaff15 | 0:66cd67db4f1b | 104 | this->fuzzyRuleAntecedent1 = fuzzyRuleAntecedent1; |
astaff15 | 0:66cd67db4f1b | 105 | this->fuzzyRuleAntecedent2 = fuzzyRuleAntecedent2; |
astaff15 | 0:66cd67db4f1b | 106 | return true; |
astaff15 | 0:66cd67db4f1b | 107 | } |
astaff15 | 0:66cd67db4f1b | 108 | return false; |
astaff15 | 0:66cd67db4f1b | 109 | } |
astaff15 | 0:66cd67db4f1b | 110 | |
astaff15 | 0:66cd67db4f1b | 111 | bool FuzzyRuleAntecedent::joinWithOR(FuzzyRuleAntecedent* fuzzyRuleAntecedent1, FuzzyRuleAntecedent* fuzzyRuleAntecedent2){ |
astaff15 | 0:66cd67db4f1b | 112 | if(fuzzyRuleAntecedent1 != NULL and fuzzyRuleAntecedent2 != NULL){ |
astaff15 | 0:66cd67db4f1b | 113 | this->op = OP_OR; |
astaff15 | 0:66cd67db4f1b | 114 | this->mode = MODE_FRA_FRA; |
astaff15 | 0:66cd67db4f1b | 115 | this->fuzzyRuleAntecedent1 = fuzzyRuleAntecedent1; |
astaff15 | 0:66cd67db4f1b | 116 | this->fuzzyRuleAntecedent2 = fuzzyRuleAntecedent2; |
astaff15 | 0:66cd67db4f1b | 117 | return true; |
astaff15 | 0:66cd67db4f1b | 118 | } |
astaff15 | 0:66cd67db4f1b | 119 | return false; |
astaff15 | 0:66cd67db4f1b | 120 | } |
astaff15 | 0:66cd67db4f1b | 121 | |
astaff15 | 0:66cd67db4f1b | 122 | float FuzzyRuleAntecedent::evaluate(){ |
astaff15 | 0:66cd67db4f1b | 123 | switch(this->mode){ |
astaff15 | 0:66cd67db4f1b | 124 | case MODE_FS: |
astaff15 | 0:66cd67db4f1b | 125 | return this->fuzzySet1->getPertinence(); |
astaff15 | 0:66cd67db4f1b | 126 | break; |
astaff15 | 0:66cd67db4f1b | 127 | case MODE_FS_FS: |
astaff15 | 0:66cd67db4f1b | 128 | switch(this->op){ |
astaff15 | 0:66cd67db4f1b | 129 | case OP_AND: |
astaff15 | 0:66cd67db4f1b | 130 | if(this->fuzzySet1->getPertinence() > 0.0 and this->fuzzySet2->getPertinence() > 0.0){ |
astaff15 | 0:66cd67db4f1b | 131 | if(this->fuzzySet1->getPertinence() < this->fuzzySet2->getPertinence()){ |
astaff15 | 0:66cd67db4f1b | 132 | return this->fuzzySet1->getPertinence(); |
astaff15 | 0:66cd67db4f1b | 133 | }else{ |
astaff15 | 0:66cd67db4f1b | 134 | return this->fuzzySet2->getPertinence(); |
astaff15 | 0:66cd67db4f1b | 135 | } |
astaff15 | 0:66cd67db4f1b | 136 | }else{ |
astaff15 | 0:66cd67db4f1b | 137 | return 0.0; |
astaff15 | 0:66cd67db4f1b | 138 | } |
astaff15 | 0:66cd67db4f1b | 139 | break; |
astaff15 | 0:66cd67db4f1b | 140 | case OP_OR: |
astaff15 | 0:66cd67db4f1b | 141 | if(this->fuzzySet1->getPertinence() > 0.0 or this->fuzzySet2->getPertinence() > 0.0){ |
astaff15 | 0:66cd67db4f1b | 142 | if(this->fuzzySet1->getPertinence() > this->fuzzySet2->getPertinence()){ |
astaff15 | 0:66cd67db4f1b | 143 | return this->fuzzySet1->getPertinence(); |
astaff15 | 0:66cd67db4f1b | 144 | }else{ |
astaff15 | 0:66cd67db4f1b | 145 | return this->fuzzySet2->getPertinence(); |
astaff15 | 0:66cd67db4f1b | 146 | } |
astaff15 | 0:66cd67db4f1b | 147 | }else{ |
astaff15 | 0:66cd67db4f1b | 148 | return 0.0; |
astaff15 | 0:66cd67db4f1b | 149 | } |
astaff15 | 0:66cd67db4f1b | 150 | break; |
astaff15 | 0:66cd67db4f1b | 151 | default: |
astaff15 | 0:66cd67db4f1b | 152 | return 0.0; |
astaff15 | 0:66cd67db4f1b | 153 | } |
astaff15 | 0:66cd67db4f1b | 154 | break; |
astaff15 | 0:66cd67db4f1b | 155 | case MODE_FS_FRA: |
astaff15 | 0:66cd67db4f1b | 156 | switch(this->op){ |
astaff15 | 0:66cd67db4f1b | 157 | case OP_AND: |
astaff15 | 0:66cd67db4f1b | 158 | if(this->fuzzySet1->getPertinence() > 0.0 and fuzzyRuleAntecedent1->evaluate() > 0.0){ |
astaff15 | 0:66cd67db4f1b | 159 | if(this->fuzzySet1->getPertinence() < fuzzyRuleAntecedent1->evaluate()){ |
astaff15 | 0:66cd67db4f1b | 160 | return this->fuzzySet1->getPertinence(); |
astaff15 | 0:66cd67db4f1b | 161 | }else{ |
astaff15 | 0:66cd67db4f1b | 162 | return fuzzyRuleAntecedent1->evaluate(); |
astaff15 | 0:66cd67db4f1b | 163 | } |
astaff15 | 0:66cd67db4f1b | 164 | }else{ |
astaff15 | 0:66cd67db4f1b | 165 | return 0.0; |
astaff15 | 0:66cd67db4f1b | 166 | } |
astaff15 | 0:66cd67db4f1b | 167 | break; |
astaff15 | 0:66cd67db4f1b | 168 | case OP_OR: |
astaff15 | 0:66cd67db4f1b | 169 | if(this->fuzzySet1->getPertinence() > 0.0 or fuzzyRuleAntecedent1->evaluate() > 0.0){ |
astaff15 | 0:66cd67db4f1b | 170 | if(this->fuzzySet1->getPertinence() > fuzzyRuleAntecedent1->evaluate()){ |
astaff15 | 0:66cd67db4f1b | 171 | return this->fuzzySet1->getPertinence(); |
astaff15 | 0:66cd67db4f1b | 172 | }else{ |
astaff15 | 0:66cd67db4f1b | 173 | return fuzzyRuleAntecedent1->evaluate(); |
astaff15 | 0:66cd67db4f1b | 174 | } |
astaff15 | 0:66cd67db4f1b | 175 | }else{ |
astaff15 | 0:66cd67db4f1b | 176 | return 0.0; |
astaff15 | 0:66cd67db4f1b | 177 | } |
astaff15 | 0:66cd67db4f1b | 178 | break; |
astaff15 | 0:66cd67db4f1b | 179 | default: |
astaff15 | 0:66cd67db4f1b | 180 | return 0.0; |
astaff15 | 0:66cd67db4f1b | 181 | } |
astaff15 | 0:66cd67db4f1b | 182 | break; |
astaff15 | 0:66cd67db4f1b | 183 | case MODE_FRA_FRA: |
astaff15 | 0:66cd67db4f1b | 184 | switch(this->op){ |
astaff15 | 0:66cd67db4f1b | 185 | case OP_AND: |
astaff15 | 0:66cd67db4f1b | 186 | if(fuzzyRuleAntecedent1->evaluate() > 0.0 and fuzzyRuleAntecedent2->evaluate() > 0.0){ |
astaff15 | 0:66cd67db4f1b | 187 | if(fuzzyRuleAntecedent1->evaluate() < fuzzyRuleAntecedent2->evaluate()){ |
astaff15 | 0:66cd67db4f1b | 188 | return fuzzyRuleAntecedent1->evaluate(); |
astaff15 | 0:66cd67db4f1b | 189 | }else{ |
astaff15 | 0:66cd67db4f1b | 190 | return fuzzyRuleAntecedent2->evaluate(); |
astaff15 | 0:66cd67db4f1b | 191 | } |
astaff15 | 0:66cd67db4f1b | 192 | }else{ |
astaff15 | 0:66cd67db4f1b | 193 | return 0.0; |
astaff15 | 0:66cd67db4f1b | 194 | } |
astaff15 | 0:66cd67db4f1b | 195 | break; |
astaff15 | 0:66cd67db4f1b | 196 | case OP_OR: |
astaff15 | 0:66cd67db4f1b | 197 | if(fuzzyRuleAntecedent1->evaluate() > 0.0 or fuzzyRuleAntecedent2->evaluate() > 0.0){ |
astaff15 | 0:66cd67db4f1b | 198 | if(fuzzyRuleAntecedent1->evaluate() > fuzzyRuleAntecedent2->evaluate()){ |
astaff15 | 0:66cd67db4f1b | 199 | return fuzzyRuleAntecedent1->evaluate(); |
astaff15 | 0:66cd67db4f1b | 200 | }else{ |
astaff15 | 0:66cd67db4f1b | 201 | return fuzzyRuleAntecedent2->evaluate(); |
astaff15 | 0:66cd67db4f1b | 202 | } |
astaff15 | 0:66cd67db4f1b | 203 | }else{ |
astaff15 | 0:66cd67db4f1b | 204 | return 0.0; |
astaff15 | 0:66cd67db4f1b | 205 | } |
astaff15 | 0:66cd67db4f1b | 206 | break; |
astaff15 | 0:66cd67db4f1b | 207 | default: |
astaff15 | 0:66cd67db4f1b | 208 | return 0.0; |
astaff15 | 0:66cd67db4f1b | 209 | } |
astaff15 | 0:66cd67db4f1b | 210 | break; |
astaff15 | 0:66cd67db4f1b | 211 | default: |
astaff15 | 0:66cd67db4f1b | 212 | return 0.0; |
astaff15 | 0:66cd67db4f1b | 213 | } |
astaff15 | 0:66cd67db4f1b | 214 | return 0.0; |
astaff15 | 0:66cd67db4f1b | 215 | } |