FADPControl.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2010, LABUST, UNIZG-FER
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of the LABUST nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  *
00034  *  Author: Dula Nad
00035  *  Created: 01.02.2013.
00036  *********************************************************************/
00037 #include <labust/control/HLControl.hpp>
00038 #include <labust/control/EnablePolicy.hpp>
00039 #include <labust/control/WindupPolicy.hpp>
00040 #include <labust/control/PIFFController.h>
00041 #include <labust/control/IPFFController.h>
00042 #include <labust/math/NumberManipulation.hpp>
00043 #include <labust/tools/MatrixLoader.hpp>
00044 #include <labust/tools/conversions.hpp>
00045 
00046 #include <Eigen/Dense>
00047 #include <auv_msgs/BodyForceReq.h>
00048 #include <std_msgs/Float32.h>
00049 #include <ros/ros.h>
00050 
00051 namespace labust
00052 {
00053         namespace control{
00055                 struct FADPControl : DisableAxis
00056                 {
00057                         enum {x=0,y};
00058 
00059                         FADPControl():Ts(0.1), useIP(false){};
00060 
00061                         void init()
00062                         {
00063                                 ros::NodeHandle nh;
00064                                 initialize_controller();
00065                         }
00066 
00067                 void windup(const auv_msgs::BodyForceReq& tauAch)
00068                         {
00069                                 //Copy into controller
00070                                 con[x].windup = tauAch.disable_axis.x;
00071                                 con[y].windup = tauAch.disable_axis.y;
00072                         };
00073 
00074                 void reset(const auv_msgs::NavSts& ref, const auv_msgs::NavSts& state)
00075                 {
00076                         con[x].internalState = 0;
00077                         con[y].internalState = 0;
00078                         con[x].lastState = state.position.north;
00079                         con[y].lastState = state.position.east;
00080                 };
00081 
00082                         auv_msgs::BodyVelocityReqPtr step(const auv_msgs::NavSts& ref,
00083                                         const auv_msgs::NavSts& state)
00084                         {
00085                                 con[x].desired = ref.position.north;
00086                                 con[y].desired = ref.position.east;
00087 
00089                                 Eigen::Vector2f out, in;
00090                                 Eigen::Matrix2f R;
00091                                 in<<ref.body_velocity.x,ref.body_velocity.y;
00092                                 double yaw(ref.orientation.yaw);
00093                                 R<<cos(yaw),-sin(yaw),sin(yaw),cos(yaw);
00094                                 out = R*in;
00095                                 double uff = out(x);
00096                                 double vff = out(y);
00097 
00098                                 con[x].state = state.position.north;
00099                                 con[y].state = state.position.east;
00100 
00101                                 if (useIP)
00102                                 {
00103                                         IPFF_ffStep(&con[x],Ts, uff);
00104                                         IPFF_ffStep(&con[y],Ts, vff);
00105                                 }
00106                                 else
00107                                 {
00108                                         PIFF_ffStep(&con[x],Ts, uff);
00109                                         PIFF_ffStep(&con[y],Ts, vff);
00110                                 }
00111 
00112                                 auv_msgs::BodyVelocityReqPtr nu(new auv_msgs::BodyVelocityReq());
00113                                 nu->header.stamp = ros::Time::now();
00114                                 nu->goal.requester = "fadp_controller";
00115                                 labust::tools::vectorToDisableAxis(disable_axis, nu->disable_axis);
00116 
00117                                 //ROS_ERROR("Output %f %f %f %f",uff,vff,con[x].output, con[y].output);
00118 
00119                                 in<<con[x].output,con[y].output;
00120                                 yaw = state.orientation.yaw;
00121                                 R<<cos(yaw),-sin(yaw),sin(yaw),cos(yaw);
00122                                 out = R.transpose()*in;
00123 
00124                                 nu->twist.linear.x = out[0];
00125                                 nu->twist.linear.y = out[1];
00126 
00127                                 return nu;
00128                         }
00129 
00130                         void initialize_controller()
00131                         {
00132                                 ROS_INFO("Initializing dynamic positioning controller...");
00133 
00134                                 ros::NodeHandle nh;
00135                                 Eigen::Vector3d closedLoopFreq(Eigen::Vector3d::Ones());
00136                                 labust::tools::getMatrixParam(nh,"dp_controller/closed_loop_freq", closedLoopFreq);
00137                                 nh.param("dp_controller/sampling",Ts,Ts);
00138                                 nh.param("dp_controller/use_ip",useIP,useIP);
00139 
00140                                 disable_axis[x] = 0;
00141                                 disable_axis[y] = 0;
00142 
00143                                 enum {Kp=0, Ki, Kd, Kt};
00144                                 for (size_t i=0; i<2;++i)
00145                                 {
00146                                         PIDBase_init(&con[i]);
00147                                         PIFF_tune(&con[i], float(closedLoopFreq(i)));
00148                                 }
00149 
00150                                 ROS_INFO("Dynamic positioning controller initialized.");
00151                         }
00152 
00153                 private:
00154                         PIDBase con[2];
00155                         double Ts;
00156                         bool useIP;
00157                 };
00158         }}
00159 
00160 int main(int argc, char* argv[])
00161 {
00162         ros::init(argc,argv,"fadp_control");
00163 
00164         labust::control::HLControl<labust::control::FADPControl,
00165         labust::control::EnableServicePolicy,
00166         labust::control::WindupPolicy<auv_msgs::BodyForceReq> > controller;
00167         ros::spin();
00168 
00169         return 0;
00170 }
00171 
00172 
00173 


labust_control
Author(s): Gyula Nagy
autogenerated on Fri Feb 7 2014 11:36:43