approx_esc_1d.cpp
Go to the documentation of this file.
00001 /*
00002  * approx_esc_1d.cpp
00003  *
00004  *  Created on: Jul 30, 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 one dimensional approximation based extremum seeking control
00010  *
00011  * * References:
00012  * - C. Zhang and R. Ordonez, “Robust and adaptive design of numerical optimization-based extremum seeking control,” Automatica, vol. 45, pp. 634–646, 2009.
00013  * - B. Calli, W. Caarls, P. Jonker and M. Wisse, "Comparison of Extremum Seeking Control Algorithms for Robotic Applications," IROS 2012.
00014  */
00015 
00016 #include "esc_approx/approx_esc_1d.h"
00017 
00018 ApproxESC1D::ApproxESC1D(){
00019         data_size_ = 0;
00020         poly_degree_ = 0;
00021         k_grad_ = 0;
00022         init_vel_ = 0;
00023         sampling_ = 0;
00024         ptr_ = 0;
00025         initialized_ = false;
00026 }
00027 
00028 ApproxESC1D::ApproxESC1D(int data_size,int poly_degree, double k_grad, double init_vel, int sampling){
00029         init(data_size,poly_degree,k_grad,init_vel,sampling);
00030 }
00031 
00032 void ApproxESC1D::init(int data_size,int poly_degree, double k_grad, double init_vel, int sampling){
00033         data_size_ = data_size;
00034         poly_degree_ = poly_degree;
00035         k_grad_ = k_grad;
00036         init_vel_ = init_vel;
00037         sampling_ = sampling;
00038         states_.resize(data_size);
00039         obj_vals_.resize(data_size);
00040         sample_ = 0;
00041         ptr_ = 0;
00042         initialized_ = true;
00043 }
00044 
00045 std::vector<double> ApproxESC1D::step(std::vector<double> state, double obj_val){
00046         if(initialized_){
00047                 if(sample_ % sampling_ == 0){
00048 
00049                         states_(ptr_) = state[0];
00050                         obj_vals_(ptr_) = obj_val;
00051 
00052                         Eigen::MatrixXf V(data_size_,poly_degree_+1);
00053                         V = Eigen::MatrixXf::Zero(data_size_, poly_degree_+1);
00054 
00055                         for (int i = 0; i<data_size_; i++)
00056                                 for (int j = 0; j<poly_degree_+1; j++)
00057                                         V(i,j) = std::pow(states_(i),(poly_degree_-j));
00058 
00059                         Eigen::VectorXf coef(data_size_);
00060 
00061                         coef = V.colPivHouseholderQr().solve(obj_vals_);
00062                         state_curr_ = states_(ptr_);
00063                         double grad_val = 0;
00064                         Eigen::VectorXf vec(data_size_);
00065 
00066                         for (int i = 0; i<poly_degree_; i++)
00067                                 grad_val = grad_val + coef(i)*(poly_degree_-i)*std::pow(state_curr_,(poly_degree_-i-1));
00068 
00069                         if (sample_<sampling_*data_size_+1){
00070                                 vel_ref_ = init_vel_;
00071                         }
00072                         else{
00073                                 vel_ref_ = -k_grad_*grad_val;
00074                                 if (vel_ref_!= vel_ref_)
00075                                         vel_ref_ = 0;
00076                         }
00077 
00078                         sample_ = sample_+1;
00079                         ptr_ = ptr_+1;
00080                         if(ptr_>=data_size_)
00081                                 ptr_ = 0;
00082 
00083                         std::vector<double> out;
00084                         out.push_back(vel_ref_);
00085                         return out;
00086                 }
00087                 else{
00088                         sample_ = sample_+1;
00089                         std::vector<double> out;
00090                         out.push_back(vel_ref_);
00091                         return out;
00092                 }
00093         }
00094         else{
00095                 fprintf(stderr,"The approximation based ESC (1D) is not initialized... It will not be executed. \n");
00096                 return std::vector<double>();
00097         }
00098 }
00099 
00100 ESC::inputType ApproxESC1D::getInputType(){
00101         return ESC::inputStateValue;
00102 }
00103 ESC::outputType ApproxESC1D::getOutputType(){
00104         return ESC::outputVelocity;
00105 }
00106 
00107 std::vector<double> ApproxESC1D::monitor(){
00108         return std::vector<double> ();
00109 }
00110 std::vector<std::string> ApproxESC1D::monitorNames(){
00111         return std::vector<std::string>();
00112 }
00113 
00114 void ApproxESC1D::reset(){
00115         sample_ = 0;
00116         ptr_ = 0;
00117 }


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