ESControlEKF_MODEL_UV.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002  * ESControlEKF_MODEL_UV.cpp
00003  *
00004  *  Created on: Jan 13, 2015
00005  *      Author: Filip Mandic
00006  *
00007  ********************************************************************/
00008 
00009 /*********************************************************************
00010  * Software License Agreement (BSD License)
00011  *
00012  *  Copyright (c) 2015, 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 #include <labust/control/esc/EscEKFModel.hpp>
00044 #include <labust/control/HLControl.hpp>
00045 #include <labust/control/EnablePolicy.hpp>
00046 #include <labust/control/WindupPolicy.hpp>
00047 #include <labust/math/NumberManipulation.hpp>
00048 #include <labust/tools/MatrixLoader.hpp>
00049 #include <labust/tools/conversions.hpp>
00050 
00051 #include <Eigen/Dense>
00052 #include <auv_msgs/BodyForceReq.h>
00053 #include <std_msgs/Float32.h>
00054 #include <ros/ros.h>
00055 
00056 namespace labust{
00057         namespace control{
00058 
00059                 /*************************************************************
00060                  *** Extremum seeking controller with speed control inputs.
00061                  ************************************************************/
00062 
00063                 struct ESControlEKF_MODEL_UV : DisableAxis{
00064 
00065                         enum {x = 0, y};
00066 
00067                         ESControlEKF_MODEL_UV():Ts(0.1), esc_controller(2,Ts),newRange(false), esc_Ts(1.0){};
00068 
00069                         void init(){
00070 
00071                                 ros::NodeHandle nh;
00072                                 initialize_controller();
00073                                 subRange = nh.subscribe<std_msgs::Float32>("range",1,& ESControlEKF_MODEL_UV::onRange,this);
00074                         }
00075 
00076                         void onRange(const std_msgs::Float32::ConstPtr& msg){
00077                                                 newRange = true;
00078                                         }
00079 
00080                         void windup(const auv_msgs::BodyForceReq& tauAch){
00081 
00082                         };
00083 
00084                         void idle(const std_msgs::Float32& ref, const auv_msgs::NavSts& state,
00085                                         const auv_msgs::BodyVelocityReq& track){
00086 
00087                         };
00088 
00089                         void reset(const std_msgs::Float32& ref, const auv_msgs::NavSts& state){
00090 
00091                         };
00092 
00093                         auv_msgs::BodyVelocityReqPtr step(const std_msgs::Float32& ref, const auv_msgs::NavSts& state){
00094 
00095                                 Eigen::Vector2d out, in, vel, velb;
00096                                 Eigen::Matrix2d R;
00097 
00098                                 double yaw = state.orientation.yaw;
00099                                 R<<cos(yaw),-sin(yaw),sin(yaw),cos(yaw);
00100 
00101                                 velb << state.gbody_velocity.x, state.gbody_velocity.y;
00102                                 vel = R*velb;
00103 
00104                                 Eigen::VectorXd input(4);
00105                                 input << state.position.north, state.position.east, vel;
00106 
00107                                 in = esc_controller.step(ref.data, input);
00108 
00109                                 auv_msgs::BodyVelocityReqPtr nu(new auv_msgs::BodyVelocityReq());
00110                                 nu->header.stamp = ros::Time::now();
00111                                 nu->goal.requester = "esc_ekf_model_controller";
00112                                 labust::tools::vectorToDisableAxis(disable_axis, nu->disable_axis);
00113 
00114 
00115                                 out = R.transpose()*in;
00116 
00117                                 nu->twist.linear.x = out[x];
00118                                 nu->twist.linear.y = out[y];
00119 
00120                                 return nu;
00121                         }
00122 
00123                         void initialize_controller(){
00124 
00125                                 ROS_INFO("Initializing extremum seeking controller...");
00126 
00127                                 ros::NodeHandle nh;
00128 
00129                                 double sin_amp = 0.1;
00130                                 double  sin_freq = 0.09;
00131                                 double  corr_gain =  -0.015;
00132                                 double  high_pass_pole = 3;
00133                                 double  low_pass_pole = 0;
00134                                 double  comp_zero =  0;
00135                                 double  comp_pole = 0;
00136                                 double sampling_time = 0.1;
00137 
00138                                 std::vector<double> Q, R;
00139                                 Q.assign(3,1);
00140                                 R.assign(3,1);
00141 
00142                                 nh.param("esc_ekf_model/sin_amp", sin_amp, sin_amp);
00143                                 nh.param("esc_ekf_model/sin_freq", sin_freq, sin_freq);
00144                                 nh.param("esc_ekf_model/corr_gain", corr_gain, corr_gain);
00145                                 nh.param("esc_ekf_model/high_pass_pole", high_pass_pole, high_pass_pole);
00146                                 nh.param("esc_ekf_model/low_pass_pole", low_pass_pole, low_pass_pole);
00147                                 nh.param("esc_ekf_model/comp_zero", comp_zero, comp_zero);
00148                                 nh.param("esc_ekf_model/comp_pole", comp_pole, comp_pole);
00149                                 nh.param("esc_ekf_model/sampling_time", sampling_time, sampling_time);
00150                                 nh.param("esc_ekf_model/Q", Q, Q);
00151                                 nh.param("esc_ekf_model/R", R, R);
00152 
00153                                 esc::EscEkfGradModel::vector Q0(3);
00154                                 Q0 << Q[0],Q[1],Q[2];
00155                                 esc::EscEkfGradModel::vector R0(3);
00156                                 R0 << R[0],R[1],R[2];
00157 
00158                                 esc_controller.initController(sin_amp, sin_freq, corr_gain, high_pass_pole, low_pass_pole, comp_zero, comp_pole, sampling_time, Q0, R0);
00159 
00160                                 disable_axis[x] = 0;
00161                                 disable_axis[y] = 0;
00162 
00163                                 ROS_INFO("Extremum seeking controller initialized.");
00164                         }
00165 
00166                 private:
00167 
00168                         double Ts;
00169                         esc::EscEkfGradModel esc_controller;
00170                         double esc_Ts;
00171                                                 bool newRange;
00172                                                 ros::Subscriber subRange;
00173 
00174                 };
00175         }
00176 }
00177 
00178 int main(int argc, char* argv[])
00179 {
00180         ros::init(argc,argv,"esc_classic_control");
00181 
00182         /***
00183         template <
00184                         class Controller,
00185                         class Enable = NoEnable,
00186                         class Windup = NoWindup,
00187                         class OutputType = auv_msgs::BodyVelocityReq,
00188                         class InputType = auv_msgs::NavSts,
00189                         class ReferenceType = auv_msgs::NavSts
00190                         >
00191         ***/
00192 
00193         labust::control::HLControl<labust::control::ESControlEKF_MODEL_UV,
00194         labust::control::EnableServicePolicy,
00195         labust::control::NoWindup,
00196         auv_msgs::BodyVelocityReq,
00197         auv_msgs::NavSts,
00198         std_msgs::Float32> controller;
00199         ros::spin();
00200 
00201         return 0;
00202 }
00203 
00204 
00205 


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