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{
00056                 struct FADPControl : DisableAxis
00057                 {
00058                         enum {x=0,y};
00059 
00060                         FADPControl():Ts(0.1),use_gvel(false),manRefNorthFlag(true),manRefEastFlag(true){};
00061 
00062                         void init()
00063                         {
00064                                 ros::NodeHandle nh;
00065                                 manRefNorthSub = nh.subscribe<std_msgs::Bool>("manRefNorthPosition",1,&FADPControl::onManNorthRef,this);
00066                                 manRefEastSub = nh.subscribe<std_msgs::Bool>("manRefEastPosition",1,&FADPControl::onManEastRef,this);
00067 
00068                                 initialize_controller();
00069                         }
00070 
00071                         void onManNorthRef(const std_msgs::Bool::ConstPtr& state)
00072                         {
00073                                 manRefNorthFlag = state->data;
00074                         }
00075 
00076                         void onManEastRef(const std_msgs::Bool::ConstPtr& state)
00077                         {
00078                                 manRefEastFlag = state->data;
00079                         }
00080 
00081 
00082                         void windup(const auv_msgs::BodyForceReq& tauAch)
00083                         {
00084                                 //Copy into controller
00085                                 bool joint_windup = tauAch.windup.x || tauAch.windup.y;
00086                                 con[x].extWindup = joint_windup;
00087                                 con[y].extWindup = joint_windup;
00088                         };
00089 
00090                         void idle(const auv_msgs::NavSts& ref, const auv_msgs::NavSts& state,
00091                                                         const auv_msgs::BodyVelocityReq& track)
00092                         {
00093                                 //Tracking external commands while idle (bumpless)
00094                                 Eigen::Vector2f out, in;
00095                                 Eigen::Matrix2f R;
00096                                 in<<track.twist.linear.x,track.twist.linear.y;
00097                                 double yaw(state.orientation.yaw);
00098                                 R<<cos(yaw),-sin(yaw),sin(yaw),cos(yaw);
00099                                 out = R*in;
00100                                 con[x].desired = state.position.north;
00101                                 con[y].desired = state.position.east;
00102                                 con[x].track = out(0);
00103                                 con[y].track = out(1);
00104                                 con[x].state = state.position.north;
00105                                 con[y].state = state.position.east;
00106 
00107                                 in<<ref.body_velocity.x,ref.body_velocity.y;
00108                                 yaw = ref.orientation.yaw;
00109                                 R<<cos(yaw),-sin(yaw),sin(yaw),cos(yaw);
00110                                 out = R*in;
00111                                 PIFF_ffIdle(&con[x],Ts, float(out(x)));
00112                                 PIFF_ffIdle(&con[y],Ts, float(out(y)));
00113                         };
00114 
00115                         void reset(const auv_msgs::NavSts& ref, const auv_msgs::NavSts& state)
00116                         {
00117                                 //UNUSED
00118                         };
00119 
00120                         auv_msgs::BodyVelocityReqPtr step(const auv_msgs::NavSts& ref,
00121                                                         const auv_msgs::NavSts& state)
00122                         {
00123                                 con[x].desired = ref.position.north;
00124                                 con[y].desired = ref.position.east;
00125                                 con[x].state = state.position.north;
00126                                 con[y].state = state.position.east;
00127                                 //Calculate tracking values
00128                                 Eigen::Vector2f out, in;
00129                                 Eigen::Matrix2f Rb,Rr;
00130                                 if (use_gvel)
00131                                 {
00132                                         in<<state.gbody_velocity.x,state.gbody_velocity.y;
00133                                 }
00134                                 else
00135                                 {
00136                                         in<<state.body_velocity.x,state.body_velocity.y;
00137                                 }
00138                                 double yaw(state.orientation.yaw);
00139                                 Rb<<cos(yaw),-sin(yaw),sin(yaw),cos(yaw);
00140                                 out = Rb*in;
00141                                 con[x].track = out(x);
00142                                 con[y].track = out(y);
00143                                 //Calculate feed forward
00144                                 in<<ref.body_velocity.x,ref.body_velocity.y;
00145                                 yaw = ref.orientation.yaw;
00146                                 Rr<<cos(yaw),-sin(yaw),sin(yaw),cos(yaw);
00147                                 out = Rr*in;
00148                                 //Make step
00149 
00150                                 //Publish commands
00151                                 double tmp_output_x, tmp_output_y;
00152                                 auv_msgs::BodyVelocityReqPtr nu(new auv_msgs::BodyVelocityReq());
00153 
00154                                 if(manRefNorthFlag)
00155                                 {
00156                                         PIFF_ffStep(&con[x], Ts, float(out(x)));
00157                                         tmp_output_x = con[x].output;
00158                                 }
00159                                 else
00160                                 {
00161                                         PIFF_ffIdle(&con[x],Ts, float(out(x)));
00162                                         tmp_output_x = out(x);
00163                                 }
00164 
00165                                 if(manRefEastFlag){
00166                                         PIFF_ffStep(&con[y], Ts, float(out(y)));
00167                                         tmp_output_y = con[y].output;
00168                                 }
00169                                 else
00170                                 {
00171                                         PIFF_ffIdle(&con[y],Ts, float(out(y)));
00172                                         tmp_output_y = out(y);
00173                                 }
00174 
00175                                 //Publish commands
00176                                 nu->header.stamp = ros::Time::now();
00177                                 nu->goal.requester = "fadp_controller";
00178                                 labust::tools::vectorToDisableAxis(disable_axis, nu->disable_axis);
00179                                 in<<tmp_output_x,tmp_output_y;
00180                                 out = Rb.transpose()*in;
00181 
00182                                 nu->twist.linear.x = out[0];
00183                                 nu->twist.linear.y = out[1];
00184 
00185                                 return nu;
00186                         }
00187 
00188                         void initialize_controller()
00189                         {
00190                                 ROS_INFO("Initializing dynamic positioning controller...");
00191 
00192                                 ros::NodeHandle nh;
00193                                 Eigen::Vector3d closedLoopFreq(Eigen::Vector3d::Ones());
00194                                 labust::tools::getMatrixParam(nh,"dp_controller/closed_loop_freq", closedLoopFreq);
00195                                 nh.param("dp_controller/sampling",Ts,Ts);
00196                                 nh.param("velocity_controller/use_ground_vel", use_gvel, use_gvel);
00197 
00198                                 disable_axis[x] = 0;
00199                                 disable_axis[y] = 0;
00200 
00201                                 for (size_t i=0; i<2;++i)
00202                                 {
00203                                         PIDBase_init(&con[i]);
00204                                         PIFF_tune(&con[i], float(closedLoopFreq(i)));
00205                                 }
00206 
00207                                 ROS_INFO("Dynamic positioning controller initialized.");
00208                         }
00209 
00210                 private:
00211                         PIDBase con[2];
00212                         double Ts;
00213                         bool use_gvel;
00214                         ros::Subscriber manRefNorthSub, manRefEastSub;
00215                         bool manRefNorthFlag, manRefEastFlag;
00216 
00217                 };
00218         }}
00219 
00220 int main(int argc, char* argv[])
00221 {
00222         ros::init(argc,argv,"fadp_control");
00223 
00224         labust::control::HLControl<labust::control::FADPControl,
00225         labust::control::EnableServicePolicy,
00226         labust::control::WindupPolicy<auv_msgs::BodyForceReq> > controller;
00227         ros::spin();
00228 
00229         return 0;
00230 }
00231 
00232 
00233 


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