approx_esc_2d.h
Go to the documentation of this file.
00001 /*
00002  * approx_esc_2d.h
00003  *
00004  *  Created on: Jul 31, 2012
00005  *      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  * Header file of the 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 
00017 #ifndef APPROX_ESC_2D_H_
00018 #define APPROX_ESC_2D_H_
00019 
00020 #include "esc_common/esc.h"
00021 #include <vector>
00022 #include <eigen3/Eigen/Dense>
00023 #include "stdio.h"
00024 class ApproxESC2D:public ESC{
00025 protected:
00026         int data_size_,sampling_;
00027         double k_grad_, init_vel_;
00028         bool initialized_;
00029         int sample_, ptr_;
00030         Eigen::MatrixXf states_;
00031         Eigen::VectorXf obj_vals_;
00032         Eigen::VectorXf vel_ref_,state_curr_;
00033 public:
00034         ApproxESC2D();
00035         ApproxESC2D(int data_size, double k_grad, double init_vel, int sampling = 1);
00036         void init(int data_size, double k_grad, double init_vel, int sampling = 1);
00037         std::vector<double>  step(std::vector<double> state, double obj_val);
00038         inputType getInputType();
00039         outputType getOutputType();
00040         std::vector<double> monitor();
00041         std::vector<std::string> monitorNames();
00042         void reset();
00043 
00044 };
00045 
00046 
00047 #endif /* APPROX_ESC_2D_H_ */


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