EscBoundedBase.hpp
Go to the documentation of this file.
00001 /*********************************************************************
00002  * EscBounded.hpp
00003  *
00004  *  Created on: Jan 30, 2015
00005  *      Author: Filip Mandic
00006  *
00007  ********************************************************************/
00008 
00009 /*********************************************************************
00010 * Software License Agreement (BSD License)
00011 *
00012 *  Copyright (c) 2014, LABUST, UNIZG-FER
00013 *  All rights reserved.
00014 *
00015 *  Redistribution and use in source and binary forms, with or without
00016 *  modification, are permitted provided that the following conditions
00017 *  are met:
00018 *
00019 *   * Redistributions of source code must retain the above copyright
00020 *     notice, this list of conditions and the following disclaimer.
00021 *   * Redistributions in binary form must reproduce the above
00022 *     copyright notice, this list of conditions and the following
00023 *     disclaimer in the documentation and/or other materials provided
00024 *     with the distribution.
00025 *   * Neither the name of the LABUST nor the names of its
00026 *     contributors may be used to endorse or promote products derived
00027 *     from this software without specific prior written permission.
00028 *
00029 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00030 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00031 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00032 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00033 *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00034 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00035 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00036 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00037 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00038 *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00039 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00040 *  POSSIBILITY OF SUCH DAMAGE.
00041 *********************************************************************/
00042 
00043 #ifndef ESCBOUNDEDBASE_HPP_
00044 #define ESCBOUNDEDBASE_HPP_
00045 
00046 #include <Eigen/Dense>
00047 #include <stdint.h>
00048 
00049 namespace labust{
00050         namespace control{
00051                 namespace esc{
00052 
00053                 /*************************************************************
00054                  *** Abstract class definition
00055                  ************************************************************/
00056                         template <typename precission = double>
00057                         class EscBoundedBase {
00058 
00059                         public:
00060 
00061                                 typedef precission numericprecission;
00062 
00063                                 typedef Eigen::Matrix<precission, Eigen::Dynamic, Eigen::Dynamic> matrix;
00064                                 typedef Eigen::Matrix<precission, Eigen::Dynamic, 1> vector;
00065 
00066                                 EscBoundedBase(int ctrlNum, numericprecission Ts):Ts_(Ts),cycle_count_(0),controlNum(ctrlNum){
00067 
00068                                         state_initialized_ = false;
00069                                         initialized_ = false;
00070                                         old_vals_initialized_ = false;
00071                                 }
00072 
00073                             virtual ~EscBoundedBase(){}
00074 
00075                                 /*****************************************************
00076                                  *** Class functions
00077                                  ****************************************************/
00078 
00079                                  virtual vector generateControl(numericprecission argument){
00080                                          //control_ = control_+gain_.cwiseProduct(postFiltered)*Ts_;
00081                                          return vector::Zero(controlNum);
00082                                  }
00083 
00084                                  virtual numericprecission calculateArgument(numericprecission cost){
00085                                          return K_*cost+omega_*Ts_*cycle_count_;
00086                                  }
00087 
00088                                  virtual vector step(numericprecission cost_signal, vector additional_input = vector::Zero(2) ){
00089 
00090                                          numericprecission argument =  calculateArgument(cost_signal);
00091                                          vector controlInput =  generateControl(argument);
00092 
00093                                          old_vals_initialized_ = true;
00094                                          cycle_count_++;
00095 
00096                                          return controlInput;
00097                                  }
00098 
00099                                 virtual void reset(){
00100 
00101                                         state_initialized_ = false;
00102                                         initialized_ = false;
00103                                         old_vals_initialized_ = false;
00104                                         cycle_count_ = 0;
00105                                 }
00106 
00107                                 /*****************************************************
00108                                  *** General parameters
00109                                  ****************************************************/
00110 
00111                                 /*** Sampling time */
00112                                 numericprecission Ts_;
00113 
00114                                 /*** Cycle */
00115                                 uint32_t cycle_count_;
00116 
00117                                 /*** Status flags */
00118                                 bool state_initialized_, initialized_, old_vals_initialized_;
00119 
00120                                 /*** Number of control inputs (states) */
00121                                 int controlNum;
00122 
00123                                 /*** ES variables */
00124                                 numericprecission K_, omega_, alpha_;
00125 
00126 
00127                         };
00128                 }
00129         }
00130 }
00131 
00132 
00133 #endif /* ESCBOUNDED_HPP_ */


labust_control
Author(s): Gyula Nagy
autogenerated on Fri Aug 28 2015 11:22:42