approx_esc_2d.cpp
Go to the documentation of this file.
00001 /*
00002  * approx_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 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_2d.h"
00017 
00018 ApproxESC2D::ApproxESC2D(){
00019         data_size_ = 0;
00020         k_grad_ = 0;
00021         init_vel_ = 0;
00022         sampling_ = 0;
00023         ptr_ = 0;
00024         initialized_ = false;
00025 }
00026 
00027 ApproxESC2D::ApproxESC2D(int data_size, double k_grad, double init_vel, int sampling){
00028         init(data_size,k_grad,init_vel,sampling);
00029 }
00030 
00031 void ApproxESC2D::init(int data_size, double k_grad, double init_vel, int sampling){
00032         data_size_ = data_size;
00033         k_grad_ = k_grad;
00034         init_vel_ = init_vel;
00035         sampling_ = sampling;
00036         sample_ = 0;
00037         ptr_ = 0;
00038         states_ = Eigen::MatrixXf::Zero(2,data_size_);
00039         obj_vals_ = Eigen::VectorXf::Zero(data_size_);
00040         state_curr_.resize(2);
00041         vel_ref_.resize(2);
00042         initialized_ = true;
00043 }
00044 
00045 std::vector<double> ApproxESC2D::step(std::vector<double> state, double obj_val){
00046         if(initialized_){
00047                 if(sample_ % sampling_ == 0){
00048 
00049                         states_(0,ptr_) = state[0];
00050                         states_(1,ptr_) = state[1];
00051                         obj_vals_(ptr_) = obj_val;
00052 
00053 
00054 
00055                         if (sample_<sampling_*data_size_ ){
00056                                 vel_ref_(0) = init_vel_*2.0/3.0;
00057                                 vel_ref_(1) = init_vel_;
00058                         }/*
00059                         else if(grad_val[0]>2 || grad_val[0]<-2){
00060                                 vel_ref_(0) = init_vel_;
00061                                 vel_ref_(1) = init_vel_;
00062                         }*/
00063                         else{
00064                                 Eigen::MatrixXf V(data_size_,4);
00065                                 V = Eigen::MatrixXf::Zero(data_size_, 4);
00066 
00067                                 for (int i = 0; i<data_size_; i++){
00068                                         V(i,0) = states_(0,i)*states_(1,i);
00069                                         V(i,1) = states_(0,i);
00070                                         V(i,2) = states_(1,i);
00071                                         V(i,3) = 1;
00072                                 }
00073 
00074                                 Eigen::VectorXf coef = Eigen::VectorXf::Zero(data_size_);
00075 
00076                                 printf("V = \n");
00077                                 for (int i = 0; i<data_size_; i++)
00078                                         printf("    %f %f %f %f      %f \n",V(i,0),V(i,1),V(i,2),V(i,3),obj_vals_(i));
00079 
00080                                 //coef = V.jacobiSvd(Eigen::ComputeFullU | Eigen::ComputeFullV).solve(obj_vals_);
00081                                 coef = V.colPivHouseholderQr().solve(obj_vals_);
00082                                 state_curr_(0) = states_(0,ptr_);
00083                                 state_curr_(1) = states_(1,ptr_);
00084                                 Eigen::VectorXf grad_val =  Eigen::VectorXf::Zero(2);
00085 
00086                                 grad_val(0) = coef(0)*state_curr_(1)+coef(1);
00087                                 grad_val(1) = coef(0)*state_curr_(0)+coef(2);
00088 
00089                                 printf("grad_val[0] = %f \n",grad_val(0));
00090                                 printf("coef[0] = %f coef[1] = %f coef[2] = %f\n",coef(0),coef(1),coef(2));
00091                                 printf("in \n");
00092                                 vel_ref_ = -k_grad_*grad_val;
00093                         }
00094 
00095                         printf("\n");
00096 
00097                         sample_ = sample_+1;
00098                         ptr_ = ptr_+1;
00099                         if(ptr_>=data_size_)
00100                                 ptr_ = 0;
00101 
00102 
00103                         std::vector<double> out;
00104                         out.push_back(vel_ref_(0));
00105                         out.push_back(vel_ref_(1));
00106                         return out;
00107                 }
00108                 else{
00109                         sample_ = sample_+1;
00110                         std::vector<double> out;
00111                         out.push_back(vel_ref_(0));
00112                         out.push_back(vel_ref_(1));
00113                         return out;
00114                 }
00115         }
00116         else{
00117                 fprintf(stderr,"The approximation based ESC (1D) is not initialized... It will not be executed. \n");
00118                 return std::vector<double>();
00119         }
00120 }
00121 
00122 ESC::inputType ApproxESC2D::getInputType(){
00123         return ESC::inputStateValue;
00124 }
00125 ESC::outputType ApproxESC2D::getOutputType(){
00126         return ESC::outputVelocity;
00127 }
00128 
00129 std::vector<double> ApproxESC2D::monitor(){
00130         return std::vector<double> ();
00131 }
00132 std::vector<std::string> ApproxESC2D::monitorNames(){
00133         return std::vector<std::string>();
00134 }
00135 
00136 void ApproxESC2D::reset(){
00137         sample_ = 0;
00138         ptr_ = 0;
00139         states_ = Eigen::MatrixXf::Zero(2,data_size_);
00140         obj_vals_ = Eigen::VectorXf::Zero(data_size_);
00141 }


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