ALTControl.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/PSatDController.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 ALTControl : DisableAxis
00056                 {
00057                         enum {x=0,y};
00058 
00059                         ALTControl():Ts(0.1), useIP(false), minAltitude(5){};
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.windup = tauAch.disable_axis.z;
00071                         con.extWindup = tauAch.windup.z;
00072                         };
00073 
00074                 void reset(const auv_msgs::NavSts& ref, const auv_msgs::NavSts& state)
00075                 {
00076                         con.internalState = 0;
00077                         lastRef = ref.position.depth;
00078                         if (ref.position.depth < 0)
00079                         {
00080                                 con.lastState = state.altitude;
00081                         }
00082                         else
00083                         {
00084                                 con.lastState = state.position.depth;
00085                         }
00086                 };
00087 
00088                         auv_msgs::BodyVelocityReqPtr step(const auv_msgs::NavSts& ref,
00089                                         const auv_msgs::NavSts& state)
00090                         {
00091                                 con.desired = ref.position.depth;
00092 
00093                                 //check setup
00094                                 if ((lastRef > 0) && (ref.position.depth < 0))
00095                                 {
00096                                         con.lastState = state.altitude;
00097                                         con.lastRef = -ref.position.depth;
00098                                 }
00099                                 else if ((lastRef < 0) && (ref.position.depth > 0))
00100                                 {
00101                                         con.lastState = state.position.depth;
00102                                         con.lastRef = ref.position.depth;
00103                                 }
00104                                 lastRef = ref.position.depth;
00105 
00106                                 //Check if altitude or depth reference
00107                                 float wd = state.body_velocity.z;
00108                                 if (ref.position.depth < 0)
00109                                 {
00110                                         //Altitude mode
00111                                         con.desired = -ref.position.depth;
00112                                         con.state = state.altitude;
00113                                         //\todo Check this if derivative has ok sign.
00114                                         wd = -wd;
00115                                 }
00116                                 else
00117                                 {
00118                                         //Depth mode
00119                                         con.state = state.position.depth;
00120                                 }
00121 
00122                                 //Zero feed-forward
00123                                 //PIFF_ffStep(&con,Ts,0);
00124                                 //\todo Check the derivative sign
00125                                 if (useIP)
00126                                 {
00127                                         IPFF_ffStep(&con, Ts, ref.body_velocity.z);
00128                                         ROS_INFO("Current state=%f, desired=%f, windup=%d", con.state, con.desired, con.windup);
00129                                 }
00130                                 else
00131                                 {
00132                                         PSatD_dStep(&con, Ts, 0);
00133                                         ROS_INFO("Current state=%f, desired=%f", con.state, con.desired);
00134                                 }
00135 
00136                                 auv_msgs::BodyVelocityReqPtr nu(new auv_msgs::BodyVelocityReq());
00137                                 nu->header.stamp = ros::Time::now();
00138                                 nu->goal.requester = "alt_controller";
00139                                 labust::tools::vectorToDisableAxis(disable_axis, nu->disable_axis);
00140 
00141                                 if (ref.position.depth < 0)
00142                                 {
00143                                         nu->twist.linear.z = -con.output;
00144                                 }
00145                                 else
00146                                 {
00147                                         nu->twist.linear.z = con.output;
00148                                 }
00149 
00150                                 //Safety
00151                                 if (state.altitude < minAltitude)
00152                                 {
00153                                         con.internalState = 0;
00154                                         nu->twist.linear.z = 0;
00155                                 }
00156 
00157                                 return nu;
00158                         }
00159 
00160                         void initialize_controller()
00161                         {
00162                                 ROS_INFO("Initializing depth/altitude controller...");
00163 
00164                                 ros::NodeHandle nh;
00165                                 double closedLoopFreq(1);
00166                                 nh.param("alt_controller/closed_loop_freq", closedLoopFreq, closedLoopFreq);
00167                                 nh.param("alt_controller/sampling",Ts,Ts);
00168                                 nh.param("alt_controller/use_ip",useIP,useIP);
00169                                 nh.param("alt_controller/min_altitude",minAltitude,minAltitude);
00170 
00171                                 disable_axis[2] = 0;
00172 
00173                                 PIDBase_init(&con);
00174                                 //PIFF_tune(&con, float(closedLoopFreq));
00175                                 if (useIP)
00176                                 {
00177                                         IPFF_tune(&con, float(closedLoopFreq));
00178                                 }
00179                                 else
00180                                 {
00181                                         PSatD_tune(&con, float(closedLoopFreq), 0, 1);
00182                                         con.outputLimit = 1;
00183                                 }
00184 
00185                                 ROS_INFO("Depth/Altitude controller initialized.");
00186                         }
00187 
00188                 private:
00189                         ros::Subscriber alt_sub;
00190                         PIDBase con;
00191                         double Ts;
00192                         bool useIP;
00193                         double lastRef;
00194                         double minAltitude;
00195                 };
00196         }}
00197 
00198 int main(int argc, char* argv[])
00199 {
00200         ros::init(argc,argv,"alt_control");
00201 
00202         labust::control::HLControl<labust::control::ALTControl,
00203         labust::control::EnableServicePolicy,
00204         labust::control::WindupPolicy<auv_msgs::BodyForceReq> > controller;
00205 
00206         ros::spin();
00207 
00208         return 0;
00209 }
00210 
00211 
00212 


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