UALFControl.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/PIFFController.h>
00042 #include <labust/tools/conversions.hpp>
00043 
00044 #include <tf2_ros/buffer.h>
00045 #include <tf2_ros/transform_listener.h>
00046 
00047 #include <Eigen/Dense>
00048 #include <auv_msgs/BodyVelocityReq.h>
00049 #include <auv_msgs/BodyForceReq.h>
00050 #include <geometry_msgs/TransformStamped.h>
00051 #include <geometry_msgs/Vector3Stamped.h>
00052 #include <ros/ros.h>
00053 
00054 namespace labust
00055 {
00056         namespace control{
00058                 struct UALFControl : DisableAxis
00059                 {
00060                         UALFControl():
00061                                 Ts(0.1),
00062                                 aAngle(M_PI/8),
00063                                 wh(0.2),
00064                                 underactuated(false),
00065                                 use_gvel(false),
00066                                 listener(buffer){};
00067 
00068                         void init()
00069                         {
00070                                 initialize_controller();
00071                         }
00072 
00073                         void reset(const auv_msgs::NavSts& ref, const auv_msgs::NavSts& state){};
00074 
00075                 void windup(const auv_msgs::BodyForceReq& tauAch)
00076                         {
00077                                 //Copy into controller
00078                                 //con.windup = tauAch.disable_axis.yaw;
00079                         con.extWindup = tauAch.windup.y;
00080                         };
00081 
00082                 void idle(const auv_msgs::NavSts& ref, const auv_msgs::NavSts& state,
00083                                 const auv_msgs::BodyVelocityReq& track)
00084                 {
00085                         //Tracking external commands while idle (bumpless)ΕΎ
00086                         if (!underactuated)
00087                         {
00088                                 try
00089                                 {
00090                                         geometry_msgs::TransformStamped dH;
00091                                         dH = buffer.lookupTransform("course_frame", "base_link", ros::Time(0));
00092                                         double roll, pitch, gamma;
00093                                         labust::tools::eulerZYXFromQuaternion(dH.transform.rotation,
00094                                                         roll, pitch, gamma);
00095 
00096                                         con.desired = ref.position.east;
00097                                         con.state = dH.transform.translation.y;
00098                                         Eigen::Vector2f out, in;
00099                                         Eigen::Matrix2f R;
00100                                         in<<state.body_velocity.x,state.body_velocity.y;
00101                                         out = R*in;
00102                                         con.track = out(1);
00103                                         PIFF_ffIdle(&con, Ts, 0);
00104                                 }
00105                                 catch (tf2::TransformException& ex)
00106                                 {
00107                                         ROS_WARN("%s",ex.what());
00108                                 }
00109                         }
00110                 };
00111 
00112                         auv_msgs::BodyVelocityReqPtr step(const auv_msgs::NavSts& ref,
00113                                         const auv_msgs::NavSts& state)
00114                         {
00115                                 auv_msgs::BodyVelocityReqPtr nu(new auv_msgs::BodyVelocityReq());
00116 
00117                                 if (ref.header.frame_id != "course_frame")
00118                                 {
00119                                         ROS_WARN("The reference frame id is not 'course_frame'.");
00120                                 }
00121                                 //Get the position in the line frame
00122                                 try
00123                                 {
00124                                         geometry_msgs::TransformStamped dH;
00125                                         dH = buffer.lookupTransform("course_frame", "base_link", ros::Time(0));
00126                                         double roll, pitch, gamma;
00127                                         labust::tools::eulerZYXFromQuaternion(dH.transform.rotation,
00128                                                         roll, pitch, gamma);
00129 
00130                                         con.desired = ref.position.east;
00131                                         con.state = dH.transform.translation.y;
00132 
00133                                         geometry_msgs::Vector3Stamped vdh;
00134                                         vdh.vector.y = con.state;
00135                                         vdh.header.stamp = ros::Time::now();
00136                                         dh_pub.publish(vdh);
00137 
00138                                         //Calculate desired yaw-rate
00139                                         if (underactuated)
00140                                         {
00141                                                 PSatD_tune(&con,wh,aAngle,ref.body_velocity.x);
00142                                                 double dd = -ref.body_velocity.x*sin(gamma);
00143                                                 PSatD_dStep(&con,Ts,dd);
00144                                                 //PSatD_step(&con,Ts);
00145                                                 ROS_DEBUG("Limiter: %f", con.outputLimit);
00146                                                 nu->twist.angular.z = con.output;
00147                                                 nu->twist.linear.x = ref.body_velocity.x;
00148                                         }
00149                                         else
00150                                         {
00151                                                 Eigen::Vector2f out, in;
00152                                                 Eigen::Matrix2f R;
00153                                                 if (use_gvel)
00154                                                 {
00155                                                         in<<state.gbody_velocity.x,state.gbody_velocity.y;
00156                                                 }
00157                                                 else
00158                                                 {
00159                                                         in<<state.body_velocity.x,state.body_velocity.y;
00160                                                 }
00161                                                 R<<cos(gamma),-sin(gamma),sin(gamma),cos(gamma);
00162                                                 out = R*in;
00163                                                 con.track = out(1);
00164                                                 PIFF_ffStep(&con,Ts,0);
00165                                                 double ul = ref.body_velocity.x;
00166                                                 double vl = con.output;
00167                                                 ROS_DEBUG("Command output: ul=%f, vl=%f", ul, vl);
00168 
00169                                                 in<<ul,vl;
00170                                                 ROS_DEBUG("Gamma: %f", gamma);
00171                                                 out = R.transpose()*in;
00172                                                 nu->twist.linear.x = out(0);
00173                                                 nu->twist.linear.y = out(1);
00174                                         }
00175 
00176                                         ROS_DEBUG("Command output: cmd=%f, dH=%f, ac=%f", con.output, dH.transform.translation.y,
00177                                                         dH.transform.translation.x);
00178                                 }
00179                                 catch (tf2::TransformException& ex)
00180                                 {
00181                                         ROS_WARN("%s",ex.what());
00182                                 }
00183 
00184                                 nu->header.stamp = ros::Time::now();
00185                                 nu->goal.requester = (underactuated)?"ualf_controller":"falf_controller";
00186                                 labust::tools::vectorToDisableAxis(disable_axis, nu->disable_axis);
00187 
00188                                 return nu;
00189                         }
00190 
00191                         void initialize_controller()
00192                         {
00193                                 ROS_INFO("Initializing LF controller...");
00194                                 ros::NodeHandle nh, ph("~");
00195                                 nh.param("ualf_controller/closed_loop_freq",wh,wh);
00196                                 double surge(0.1);
00197                                 nh.param("ualf_controller/default_surge",surge,surge);
00198                         nh.param("ualf_controller/approach_angle",aAngle,aAngle);
00199                                 nh.param("ualf_controller/sampling",Ts,Ts);
00200                                 nh.param("velocity_controller/use_ground_vel", use_gvel, use_gvel);
00201                                 ph.param("underactuated",underactuated,underactuated);
00202                                 dh_pub = nh.advertise<geometry_msgs::Vector3Stamped>("dh_calc",1);
00203                                 
00204                                 PIDBase_init(&con);
00205 
00206                                 disable_axis[0] = 0;
00207                                 if (underactuated)
00208                                 {
00209                                         disable_axis[5] = 0;
00210                                         PSatD_tune(&con,wh,aAngle,surge);
00211                                 }
00212                                 else
00213                                 {
00214                                         disable_axis[1] = 0;
00215                                         PIFF_tune(&con,wh);
00216                                 }
00217                                 //con.b = 1.0;
00218 
00219                                 ROS_INFO("LF controller initialized.");
00220                         }
00221 
00222                 private:
00223                         PIDBase con;
00224                         double Ts;
00225                         double aAngle, wh;
00226                         bool underactuated;
00227                         bool use_gvel;
00228                         tf2_ros::Buffer buffer;
00229                         tf2_ros::TransformListener listener;
00230                         ros::Publisher dh_pub;
00231                 };
00232         }}
00233 
00234 int main(int argc, char* argv[])
00235 {
00236         ros::init(argc,argv,"lf_control");
00237 
00238         labust::control::HLControl<labust::control::UALFControl,
00239         labust::control::EnableServicePolicy,
00240         labust::control::WindupPolicy<auv_msgs::BodyForceReq> > controller;
00241         ros::spin();
00242 
00243         return 0;
00244 }
00245 
00246 
00247 


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