uvt_control.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/PIFFController.h>
00040 #include <labust/control/IPFFController.h>
00041 #include <labust/math/NumberManipulation.hpp>
00042 #include <labust/tools/MatrixLoader.hpp>
00043 #include <labust/tools/conversions.hpp>
00044 
00045 #include <Eigen/Dense>
00046 #include <auv_msgs/BodyForceReq.h>
00047 #include <auv_msgs/FSPathInfo.h>
00048 #include <ros/ros.h>
00049 
00050 namespace labust
00051 {
00052         namespace control{
00054                 struct UVTControl : DisableAxis
00055                 {
00056                         enum {u=0,r=5};
00057 
00058                         UVTControl():
00059                                 Ts(0.1),
00060                                 k1(1.0),
00061                                 k2(1.0),
00062                                 kpsi(1.0),
00063                                 psia(M_PI/4){};
00064 
00065                         void init()
00066                         {
00067                                 initializeController();
00068                         }
00069 
00070                         void idle(const auv_msgs::FSPathInfo& ref, const auv_msgs::NavSts& state,
00071                                                         const auv_msgs::BodyVelocityReq& track){};
00072 
00073                         void reset(const auv_msgs::FSPathInfo& ref, const auv_msgs::NavSts& state){};
00074 
00075                         auv_msgs::BodyVelocityReqPtr step(const auv_msgs::FSPathInfo& ref,
00076                                                         const auv_msgs::NavSts& state)
00077                         {
00078                                 con.desired = ref.orientation.yaw;
00079                                 con.state = (useIP?unwrap(state.orientation.yaw):state.orientation.yaw);
00080                                 con.track = state.orientation_rate.yaw;
00081 
00082                                 float errorWrap = labust::math::wrapRad(
00083                                                                 con.desired - con.state);
00084                                 //Zero feed-forward
00085                                 if (useIP)
00086                                 {
00087                                         IPFF_wffStep(&con,Ts, errorWrap, ref.orientation_rate.yaw);
00088                                 }
00089                                 else
00090                                 {
00091                                         PIFF_wffStep(&con,Ts, errorWrap, ref.orientation_rate.yaw);
00092                                 }
00093 
00094 
00095                                 auv_msgs::BodyVelocityReqPtr nu(new auv_msgs::BodyVelocityReq());
00096                                 labust::tools::vectorToDisableAxis(disable_axis, nu->disable_axis);
00097                                 nu->header.stamp = ros::Time::now();
00098                                 nu->goal.requester = "uvt_controller";
00099 
00100                                 double ddelta = -psia*kpsi*(-ref.curvature* sdot * s1 + vt*sin(psi))/cosh(kpsi*y1)^2;
00101                                 nu->twist.angular.z = ddelta - k1*(psi-delta) + 1/radius*sdot;
00102 
00103                                 return nu;
00104                         }
00105 
00106                         void initializeController()
00107                         {
00108                                 ros::NodeHandle nh;
00109                                 nh.param("uvt_controller/closed_loop_freq", closedLoopFreq, closedLoopFreq);
00110                                 nh.param("uvt_controller/sampling",Ts,Ts);
00111 
00112                                 disable_axis[r] = 0;
00113                                 disable_axis[u] = 0;
00114 
00115                                 ROS_INFO("Heading controller initialized.");
00116                         }
00117 
00118                 private:
00120                         double Ts;
00122                         double k1;
00124                         double k2;
00126                         double kpsi;
00128                         double psia;
00129                 };
00130         }}
00131 
00132 int main(int argc, char* argv[])
00133 {
00134         ros::init(argc,argv,"uvt_control");
00135 
00136         labust::control::HLControl<labust::control::UVTControl,
00137         labust::control::EnableServicePolicy,
00138         labust::control::NoWindup,
00139         auv_msgs::BodyVelocityReq,
00140         auv_msgs::NavSts,
00141         auv_msgs::SFPathInfo> controller;
00142 
00143 
00144         ros::spin();
00145 
00146         return 0;
00147 }
00148 
00149 
00150 


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