nn_esc_2d.cpp
Go to the documentation of this file.
00001 /*
00002  * nn_esc_2d.cpp
00003  *
00004  *  Created on: Jul 31, 2012
00005  *      Author: Berk Calli
00006  *      Organization: Delft Biorobotics Lab., Delft University of Technology
00007  *              Contact info: b.calli@tudelft.nl, web: www.dbl.tudelft.nl
00008  *
00009  * Class for two dimensional neural network extremum seeking control
00010  *
00011  * * References:
00012  * - M. Teixeira and S. Zak, “Analog neural nonderivative optimizers,” IEEE Transactions on Neural Networks, vol. 9, pp. 629–638, 1998.
00013  * - B. Calli, W. Caarls, P. Jonker and M. Wisse, "Comparison of Extremum Seeking Control Algorithms for Robotic Applications", IROS 2012.
00014  */
00015 #include "esc_nn/nn_esc_2d.h"
00016 
00017 NNESC2D::NNESC2D(){
00018         M_ = 0;
00019         A_ = 0;
00020         ddelta1_ = 0;
00021         ddelta2_ = 0;
00022         ddelta3_ = 0;
00023         delta_ = 0;
00024         B_ = 0;
00025         w_switch_old_ = 0;
00026         a_switch1_old_ = 0;
00027         a_switch2_old_ = 0;
00028         a_switch3_old_ = 0;
00029         yr_ = 0;
00030         period_ = 0;
00031         min_peak_ = 0;
00032         vel_ref_.resize(2);
00033         vel_ref_old_.resize(2);
00034         vel_ref_[0] = 0;
00035         vel_ref_[1] = 0;
00036         w_switch_ = 0;
00037         min_peak_detect_init_ = false;
00038         initialized_ = false;
00039 }
00040 
00041 ESC::inputType NNESC2D::getInputType(){
00042         return inputValue;
00043 }
00044 
00045 ESC::outputType NNESC2D::getOutputType(){
00046         return outputVelocity;
00047 }
00048 
00049 std::vector<double> NNESC2D::monitor(){
00050         std::vector<double> monitor_vals;
00051         monitor_vals.push_back(yr_);
00052         monitor_vals.push_back(min_peak_);
00053         monitor_vals.push_back(w_switch_);
00054         monitor_vals.push_back(yr_+ddelta1_);
00055         monitor_vals.push_back(yr_+ddelta2_);
00056         monitor_vals.push_back(yr_+ddelta3_);
00057         monitor_vals.push_back(yr_+delta_);
00058 
00059         return monitor_vals;
00060 
00061 }
00062 
00063 std::vector<std::string> NNESC2D::monitorNames(){
00064         std::vector<std::string> monitor_names;
00065         monitor_names.push_back("driving input value");
00066         monitor_names.push_back("minimum peak detector output");
00067         monitor_names.push_back("w switch value");
00068         monitor_names.push_back("threshold value 1");
00069         monitor_names.push_back("threshold value 2");
00070         monitor_names.push_back("threshold value 3");
00071         monitor_names.push_back("threshold value 4");
00072 
00073         return monitor_names;
00074 }
00075 
00076 NNESC2D::NNESC2D(double A,double M, double B, double ddelta1, double ddelta2, double ddelta3, double delta, double period, int stopping_cycle_number, double stoping_min_val){
00077         init(A, M, B, ddelta1, ddelta2, ddelta3, delta, period, stopping_cycle_number, stoping_min_val);
00078 }
00079 
00080 void NNESC2D::init(double A, double M, double B, double ddelta1, double ddelta2, double ddelta3, double delta, double period, int stopping_cycle_number, double stoping_min_val){
00081         A_ = A;
00082         M_ = M;
00083         B_ = B;
00084         ddelta1_ = ddelta1;
00085         ddelta2_ = ddelta2;
00086         ddelta3_ = ddelta3;
00087         delta_ = delta;
00088         period_ = period;
00089         reset();
00090         initialized_ = true;
00091         stopping_cycle_number_ = stopping_cycle_number;
00092         stoping_min_val_ = stoping_min_val;
00093 }
00094 
00095 std::vector<double> NNESC2D::step(double obj_val){
00096         if (!initialized_){
00097                 fprintf(stderr,"The neural network ESC (1D) is not initialized... It will not be executed. \n");
00098                 return std::vector<double>();
00099         }
00100 
00101         if(!min_peak_detect_init_){
00102                 min_peak_ = obj_val;
00103                 yr_ = min_peak_;
00104                 min_peak_detect_init_ = true;
00105                 obj_val_cycle_init_ = obj_val;
00106                 vel_ref_old_[0] = vel_ref_[0];
00107                 vel_ref_old_[1] = vel_ref_[1];
00108         }
00109 
00110         double e = yr_ - obj_val;
00111         double s[3];
00112         s[0] = aSwitch1(e);
00113         s[1] = aSwitch2(e);
00114         s[2] = aSwitch3(e);
00115 
00116         vel_ref_[1] = s[0]+s[1];
00117         vel_ref_[0] = s[1]+s[2];
00118 
00119         min_peak_ = minPeakDetect(e);
00120         w_switch_ = wSwitch(e);
00121         yr_ = yr_ + (w_switch_+min_peak_)*period_;
00122 
00123         if((vel_ref_old_[0] != vel_ref_[0] || vel_ref_old_[1] != vel_ref_[1]) && vel_ref_[1] == A_ && vel_ref_[0] == 0){
00124                 if(obj_val_cycle_init_ - obj_val < stoping_min_val_){
00125                         nn_cycle_count_++;
00126                 }
00127                 else
00128                         nn_cycle_count_ = 0;
00129                 obj_val_cycle_init_ = obj_val;
00130         }
00131         //printf("[nn_esc_2d]: nn_cycle_count = %d \n",nn_cycle_count_);
00132         vel_ref_old_[0] = vel_ref_[0];
00133         vel_ref_old_[1] = vel_ref_[1];
00134 
00135         return vel_ref_;
00136 }
00137 double NNESC2D::wSwitch(double e){
00138         if(e>delta_){
00139                 w_switch_old_ = 0;
00140                 return 0;
00141         }
00142         else if(e<-delta_){
00143                 w_switch_old_ = B_;
00144                 return B_;
00145         }
00146         else
00147                 return w_switch_old_;
00148 
00149 }
00150 
00151 double NNESC2D::minPeakDetect(double e){
00152         if(e<=0)
00153                 return 0;
00154         else
00155                 return -M_;
00156 }
00157 
00158 double NNESC2D::aSwitch1(double e){
00159         if( e < -ddelta1_ ){
00160                 a_switch1_old_ = -A_;
00161                 return -A_;
00162         }
00163         else if(e>ddelta1_){
00164                 a_switch1_old_ = A_;
00165                 return A_;
00166         }
00167         else
00168                 return a_switch1_old_;
00169 }
00170 
00171 double NNESC2D::aSwitch2(double e){
00172 
00173         if( e < -ddelta2_ ){
00174                 a_switch2_old_ = A_;
00175                 return A_;
00176 
00177         }
00178         else if(e>ddelta2_){
00179                 a_switch2_old_ = 0;
00180                 return 0;
00181         }
00182         else
00183                 return a_switch2_old_;
00184 }
00185 
00186 double NNESC2D::aSwitch3(double e){
00187         if( e < -ddelta3_ ){
00188                 a_switch3_old_ = -2*A_;
00189                 return -2*A_;
00190         }
00191         else if(e>ddelta3_){
00192                 a_switch3_old_ = 0;
00193                 return 0;
00194         }
00195         else
00196                 return a_switch3_old_;
00197 }
00198 
00199 void NNESC2D::reset(){
00200         w_switch_old_ = 0;
00201         a_switch1_old_ = A_;
00202         a_switch2_old_ = 0;
00203         a_switch3_old_ = 0;
00204         vel_ref_.resize(2);
00205         vel_ref_[0] = 0;
00206         vel_ref_[1] = 0;
00207         vel_ref_old_.resize(2);
00208         vel_ref_old_[0] = 0;
00209         vel_ref_old_[1] = 0;
00210         yr_ = 0;
00211         min_peak_ = 0;
00212         w_switch_ = 0;
00213         nn_cycle_count_ = 0;
00214         min_peak_detect_init_ = false;
00215 }
00216 
00217 bool NNESC2D::isStoppingConditionsMet(){
00218         if(stopping_cycle_number_ <= 0)
00219                 return false;
00220         else if(nn_cycle_count_ > stopping_cycle_number_){
00221                 return true;
00222         }
00223         else
00224                 return false;
00225 }


esc_nn
Author(s): Berk Calli
autogenerated on Sun Jan 5 2014 11:07:07