ESControlBounded_UV.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002  * ESControlBounded_UV.cpp
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 #include <labust/control/esc/EscBounded.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 ESCControlBounded_UV : DisableAxis{
00064 
00065                         enum {x = 0, y};
00066 
00067                         ESCControlBounded_UV():Ts(0.1), esc_controller(2,Ts), count(0),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,& ESCControlBounded_UV::onRange,this);
00074 
00075                         }
00076 
00077                         void onRange(const std_msgs::Float32::ConstPtr& msg){
00078                                 newRange = true;
00079                         }
00080 
00081                 void windup(const auv_msgs::BodyForceReq& tauAch){
00082 
00083                 };
00084 
00085                 void idle(const std_msgs::Float32& ref, const auv_msgs::NavSts& state,
00086                                 const auv_msgs::BodyVelocityReq& track){
00087 
00088                 };
00089 
00090                 void reset(const std_msgs::Float32& ref, const auv_msgs::NavSts& state){
00091 
00092                 };
00093 
00094                 auv_msgs::BodyVelocityReqPtr step(const std_msgs::Float32& ref, const auv_msgs::NavSts& state){
00095 
00096                         //if((count++)%20 == 0){
00097                                                         int t_step = esc_Ts/Ts;
00098                                                         //if(newRange){
00099                                                         if((count++)%t_step == 0){
00100 
00101                                                                 newRange = false;
00102 
00103                                 Eigen::Vector2d out, in;
00104                                 Eigen::Matrix2d R;
00105 
00106                                 in = esc_controller.step(ref.data);
00107 
00108                                 auv_msgs::BodyVelocityReqPtr nu(new auv_msgs::BodyVelocityReq());
00109                                 nu->header.stamp = ros::Time::now();
00110                                 nu->goal.requester = "esc_controller_bounded";
00111                                 labust::tools::vectorToDisableAxis(disable_axis, nu->disable_axis);
00112 
00113                                 double yaw = state.orientation.yaw;
00114                                 R<<cos(yaw),-sin(yaw),sin(yaw),cos(yaw);
00115                                 out = R.transpose()*in;
00116 
00117                                 nu->twist.linear.x = out[x];
00118                                 nu->twist.linear.y = out[y];
00119 
00120                                 nu_past = nu;
00121                                 return nu;
00122                         }else{
00123 
00124                                 ROS_ERROR("PAST");
00125                                 return nu_past;
00126                         }
00127                 }
00128 
00129                         void initialize_controller(){
00130 
00131                                 ROS_INFO("Initializing extremum seeking controller...");
00132 
00133                                 ros::NodeHandle nh;
00134 
00135 //                              double K = 1.5;
00136 //                              double  alpha = 1;
00137 //                              double  omega =  0.5;
00138 
00139 //                              double K = 1.5;
00140 //                              double  alpha = 1;
00141 //                              double  omega =  0.75;
00142 
00143                                 double K = 1.1;
00144                                 double  alpha = 0.7;
00145                                 double  omega =  0.3;
00146                                 double sampling_time = 0.1;
00147 
00148                                 nh.param("esc_bounded/K", K, K);
00149                                 nh.param("esc_bounded/alpha", alpha, alpha);
00150                                 nh.param("esc_bounded/omega", omega, omega);
00151                                 nh.param("esc_bounded/sampling_time", sampling_time, sampling_time);
00152 
00153                                 esc_Ts = sampling_time;
00154 
00155                                 esc_controller.initController(K, omega, alpha, sampling_time);
00156 
00157                                 disable_axis[x] = 0;
00158                                 disable_axis[y] = 0;
00159 
00160                                 ROS_INFO("Extremum seeking controller initialized.");
00161                         }
00162 
00163                 private:
00164 
00165                         double Ts;
00166                         esc::EscBounded esc_controller;
00167                         auv_msgs::BodyVelocityReqPtr nu_past;
00168                         int count;
00169                         double esc_Ts;
00170                                                 bool newRange;
00171                                                 ros::Subscriber subRange;
00172                 };
00173         }
00174 }
00175 
00176 int main(int argc, char* argv[])
00177 {
00178         ros::init(argc,argv,"esc_classic_control");
00179 
00180         /***
00181         template <
00182                         class Controller,
00183                         class Enable = NoEnable,
00184                         class Windup = NoWindup,
00185                         class OutputType = auv_msgs::BodyVelocityReq,
00186                         class InputType = auv_msgs::NavSts,
00187                         class ReferenceType = auv_msgs::NavSts
00188                         >
00189         ***/
00190 
00191         labust::control::HLControl<labust::control::ESCControlBounded_UV,
00192         labust::control::EnableServicePolicy,
00193         labust::control::NoWindup,
00194         auv_msgs::BodyVelocityReq,
00195         auv_msgs::NavSts,
00196         std_msgs::Float32> controller;
00197         ros::spin();
00198 
00199         return 0;
00200 }
00201 
00202 
00203 
00204 
00205 
00206 
00207 


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