perturb_esc_nd.cpp
Go to the documentation of this file.
00001 /*
00002  * perturb_esc_nd.cpp
00003  *
00004  *  Created on: Aug 1, 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 perturbation based extremum seeking control
00010  *
00011  * * References:
00012  * - K. B. Ariyur and M. Krstic, "Real-Time Optimization by Extremum-Seeking Control", Wiley, 2003.
00013  * - B. Calli, W. Caarls, P. Jonker, M. Wisse, "Comparison of Extremum Seeking Control Algorithms for Robotic Applications", IROS 2012.
00014  *
00015  */
00016 
00017 #include "esc_perturb/perturb_esc_nd.h"
00018 
00019 PerturbESCND::PerturbESCND(){
00020         sin_amp_ = 0;
00021         sin_freq_ = 0;
00022         corr_gain_ = 0;
00023         high_pass_pole_ = 0;
00024         low_pass_pole_ = 0;
00025         comp_pole_ = 0;
00026         comp_zero_ = 0;
00027         period_ = 0;
00028         state_initialized_ = false;
00029         initialized_ = false;
00030         old_vals_initialized_ = false;
00031 }
00032 PerturbESCND::PerturbESCND(double sin_amp, double sin_freq, double corr_gain, double high_pass_pole, double low_pass_pole, double comp_zero, double comp_pole, double period){
00033         init(sin_amp, sin_freq, corr_gain, high_pass_pole, low_pass_pole, comp_zero, comp_pole, period);
00034 }
00035 void PerturbESCND::init(double sin_amp, double sin_freq, double corr_gain, double high_pass_pole, double low_pass_pole, double comp_zero, double comp_pole, double period){
00036         sin_amp_ = sin_amp;
00037         sin_freq_ = sin_freq;
00038         corr_gain_ = corr_gain;
00039         high_pass_pole_ = high_pass_pole;
00040         low_pass_pole_ = low_pass_pole;
00041         comp_pole_ = comp_pole;
00042         comp_zero_ = comp_zero;
00043         period_ = period;
00044         obj_val_old_ = 0;
00045         cycle_count_ = 0;
00046         hpf_out_old_ = 0;
00047         opt_dim_ = 0;
00048         state_initialized_ = false;
00049         old_vals_initialized_ = false;
00050         initialized_ = true;
00051 }
00052 
00053 std::vector<double>  PerturbESCND::step(std::vector<double> state, double obj_val){
00054 
00055         if(!initialized_){
00056                 fprintf(stderr,"The perturbation based ESC (1D) is not initialized... It will not be executed. \n");
00057                 return std::vector<double>();
00058         }
00059 
00060         if(!state_initialized_ && state.empty()){
00061                 fprintf(stderr,"The state value of the perturbation based ESC (1D) cannot be initialized: State vector is empty. The algorithm will not be executed. \n");
00062                 return std::vector<double>();
00063         }
00064 
00065         else if(!state_initialized_){
00066 
00067                 opt_dim_ = (unsigned int)state.size();
00068                 lpf_out_old_.resize(opt_dim_);
00069                 signal_demodulated_old_.resize(opt_dim_);
00070                 comp_old_.resize(opt_dim_);
00071                 corr_signal_.resize(opt_dim_);
00072                 pos_ref_.resize(opt_dim_);
00073                 for (size_t i = 0; i<opt_dim_; i++){
00074                         pos_ref_[i] = state[i];
00075                         lpf_out_old_[i] = 0;
00076                         signal_demodulated_old_[i] = 0;
00077                         comp_old_[i] = 0;
00078                         corr_signal_[i] = 0;
00079                 }
00080 
00081                 phase_shift_.resize(opt_dim_);
00082                 phase_shift_[0] = 0;
00083                 for (size_t i = 1; i<opt_dim_; i++){
00084                         phase_shift_[i] = i*PI/((double)opt_dim_);
00085                 }
00086                 state_initialized_ = true;
00087         }
00088 
00089         double hpf_out = (-(period_*high_pass_pole_-2)*hpf_out_old_+2*obj_val-2*obj_val_old_)/(2+high_pass_pole_*period_);
00090         hpf_out_old_ = hpf_out;
00091         obj_val_old_ = obj_val;
00092         std::vector<double> signal_demodulated(opt_dim_);
00093         std::vector<double> lpf_out(opt_dim_);
00094         std::vector<double> comp_out(opt_dim_);
00095         std::vector<double> output;
00096 
00097         for (size_t i = 0; i<opt_dim_; i++){
00098                 signal_demodulated[i]= hpf_out*sin_amp_*std::sin(cycle_count_*period_*sin_freq_ + phase_shift_[i]);
00099                 lpf_out[i] = ((2.0-low_pass_pole_*period_)*lpf_out_old_[i]+low_pass_pole_*period_*signal_demodulated[i]+low_pass_pole_*period_*signal_demodulated_old_[i])/(2.0+low_pass_pole_*period_);
00100                 comp_out[i]= ((2.0+period_*comp_zero_)*lpf_out[i]+(period_*comp_zero_-2.0)*lpf_out_old_[i]-(period_*comp_pole_-2.0)*comp_old_[i])/(2.0+period_*comp_pole_);
00101                 corr_signal_[i] = corr_signal_[i]+corr_gain_*comp_out[i]*period_;
00102                 if(!old_vals_initialized_)
00103                         pos_ref_[i] = sin_amp_*std::sin(cycle_count_*period_*sin_freq_ + phase_shift_[i]);      //modulation
00104                 else
00105                         pos_ref_[i] = corr_signal_[i]+sin_amp_*std::sin(cycle_count_*period_*sin_freq_ + phase_shift_[i]);      //modulation
00106                 output.push_back(pos_ref_[i]);
00107                 signal_demodulated_old_[i] = signal_demodulated[i];
00108                 lpf_out_old_[i] = lpf_out[i];
00109                 comp_old_[i] = comp_out[i];
00110         }
00111         old_vals_initialized_ = true;
00112         cycle_count_++;
00113 
00114         return output;
00115 }
00116 
00117 ESC::inputType PerturbESCND::getInputType(){
00118         return ESC::inputStateValue;
00119 }
00120 
00121 ESC::outputType PerturbESCND::getOutputType(){
00122         return ESC::outputPosition;
00123 }
00124 
00125 std::vector<double> PerturbESCND::monitor(){
00126         std::vector<double> monitor_values;
00127 
00128         for(size_t i = 0; i<opt_dim_; i++)
00129                 monitor_values.push_back(corr_signal_[i]);
00130 
00131         return monitor_values;
00132 }
00133 std::vector<std::string> PerturbESCND::monitorNames(){
00134         std::vector<std::string> monitor_names;
00135         std::string base = "correction signal ";
00136         char numstr[21];
00137         for(size_t i = 0; i<opt_dim_; i++){
00138                 sprintf(numstr, "%zd", i+1);
00139                 monitor_names.push_back(base + numstr);
00140         }
00141 
00142         return monitor_names;
00143 }
00144 
00145 void PerturbESCND::reset(){
00146         obj_val_old_ = 0;
00147         cycle_count_ = 0;
00148         hpf_out_old_ = 0;
00149         opt_dim_ = 0;
00150         state_initialized_ = false;
00151         old_vals_initialized_ = false;
00152 }


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