FADP_3DControl.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002  * FADP_3DControl.cpp
00003  *
00004  *  Created on: Apr 16, 2015
00005  *      Author: Dula Nad, Filip Mandic
00006  *
00007  ********************************************************************/
00008 
00009 /*********************************************************************
00010  * Software License Agreement (BSD License)
00011  *
00012  *  Copyright (c) 2015, LABUST, UNIZG-FER
00013  *  All rights reserved.
00014  *
00015  *  Redistribution and use in source and binary forms, with or without
00016  *  modification, are permitted provided that the following conditions
00017  *  are met:
00018  *
00019  *   * Redistributions of source code must retain the above copyright
00020  *     notice, this list of conditions and the following disclaimer.
00021  *   * Redistributions in binary form must reproduce the above
00022  *     copyright notice, this list of conditions and the following
00023  *     disclaimer in the documentation and/or other materials provided
00024  *     with the distribution.
00025  *   * Neither the name of the LABUST nor the names of its
00026  *     contributors may be used to endorse or promote products derived
00027  *     from this software without specific prior written permission.
00028  *
00029  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00030  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00031  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00032  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00033  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00034  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00035  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00036  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00037  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00038  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00039  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00040  *  POSSIBILITY OF SUCH DAMAGE.
00041  *********************************************************************/
00042 #include <labust/control/HLControl.hpp>
00043 #include <labust/control/EnablePolicy.hpp>
00044 #include <labust/control/WindupPolicy.hpp>
00045 #include <labust/control/PIFFController.h>
00046 #include <labust/control/IPFFController.h>
00047 #include <labust/math/NumberManipulation.hpp>
00048 #include <labust/tools/MatrixLoader.hpp>
00049 #include <labust/tools/conversions.hpp>
00050 
00051 #include <Eigen/Dense>
00052 #include <auv_msgs/BodyForceReq.h>
00053 #include <std_msgs/Float32.h>
00054 #include <ros/ros.h>
00055 
00056 namespace labust
00057 {
00058         namespace control{
00061                 struct FADPControl : DisableAxis
00062                 {
00063                         enum {x=0,y, z};
00064 
00065                         FADPControl():Ts(0.1){};
00066 
00067                         void init()
00068                         {
00069                                 ros::NodeHandle nh;
00070                                 initialize_controller();
00071                         }
00072 
00073                         void windup(const auv_msgs::BodyForceReq& tauAch)
00074                         {
00075                                 bool joint_windup = tauAch.windup.x || tauAch.windup.y;
00076                                 con[x].extWindup = joint_windup;
00077                                 con[y].extWindup = joint_windup;
00078                                 con[z].extWindup = tauAch.windup.z;
00079 
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                                 Eigen::Quaternion<float> q;
00087                                 Eigen::Vector3f in, out;
00088                                 labust::tools::quaternionFromEulerZYX(
00089                                                 state.orientation.roll,
00090                                                 state.orientation.pitch,
00091                                                 state.orientation.yaw, q);
00092                                 in<<track.twist.linear.x,track.twist.linear.y,track.twist.linear.z;
00093                                 out = q.matrix()*in;
00094                                 con[x].desired = state.position.north;
00095                                 con[y].desired = state.position.east;
00096                                 con[z].desired = state.position.depth;
00097                                 con[x].track = out(x);
00098                                 con[y].track = out(y);
00099                                 con[z].track = out(z);
00100                                 con[x].state = state.position.north;
00101                                 con[y].state = state.position.east;
00102                                 con[z].state = state.position.depth;
00103 
00104                                 labust::tools::quaternionFromEulerZYX(
00105                                                 ref.orientation.roll,
00106                                                 ref.orientation.pitch,
00107                                                 ref.orientation.yaw, q);
00108                                 in<<ref.body_velocity.x,ref.body_velocity.y,ref.body_velocity.z;
00109                                 out = q.matrix()*in;
00110 
00111                                 PIFF_ffIdle(&con[x], Ts, float(out(x)));
00112                                 PIFF_ffIdle(&con[y], Ts, float(out(y)));
00113                                 PIFF_ffIdle(&con[z], Ts, float(out(z)));
00114                         };
00115 
00116                         void reset(const auv_msgs::NavSts& ref, const auv_msgs::NavSts& state)
00117                         {
00118                                 //UNUSED
00119                         };
00120 
00121                         auv_msgs::BodyVelocityReqPtr step(const auv_msgs::NavSts& ref,
00122                                                         const auv_msgs::NavSts& state)
00123                         {
00124                                 con[x].desired = ref.position.north;
00125                                 con[y].desired = ref.position.east;
00126                                 con[z].desired = ref.position.depth;
00127                                 con[x].state = state.position.north;
00128                                 con[y].state = state.position.east;
00129                                 con[z].state = state.position.depth;
00130                                 //Calculate tracking values
00131                                 Eigen::Quaternion<float> qs,qr;
00132                                 Eigen::Vector3f in, out;
00133                                 labust::tools::quaternionFromEulerZYX(
00134                                                 state.orientation.roll,
00135                                                 state.orientation.pitch,
00136                                                 state.orientation.yaw, qs);
00137                                 in<<state.body_velocity.x,state.body_velocity.y,state.body_velocity.z;
00138                                 out = qs.matrix()*in;
00139                                 con[x].track = out(x);
00140                                 con[x].track = out(y);
00141                                 con[x].track = out(z);
00142                                 //Calculate feed forward
00143                                 ROS_DEBUG("Position desired: %f %f %f", ref.position.north, ref.position.east, ref.position.depth);
00144                                 labust::tools::quaternionFromEulerZYX(
00145                                                 ref.orientation.roll,
00146                                                 ref.orientation.pitch,
00147                                                 ref.orientation.yaw, qr);
00148                                 in<<ref.body_velocity.x,ref.body_velocity.y,ref.body_velocity.z;
00149                                 out = qr.matrix()*in;
00150                                 //Make step
00151                                 PIFF_ffStep(&con[x], Ts, float(out(x)));
00152                                 PIFF_ffStep(&con[y], Ts, float(out(y)));
00153                                 PIFF_ffStep(&con[z], Ts, float(out(z)));
00154 
00155                                 //Publish commands
00156                                 auv_msgs::BodyVelocityReqPtr nu(new auv_msgs::BodyVelocityReq());
00157                                 nu->header.stamp = ros::Time::now();
00158                                 nu->goal.requester = "fadp_3d_controller";
00159                                 labust::tools::vectorToDisableAxis(disable_axis, nu->disable_axis);
00160                                 in<<con[x].output,con[y].output,con[z].output;
00161                                 out = qs.matrix()*in;
00162                                 nu->twist.linear.x = out[x];
00163                                 nu->twist.linear.y = out[y];
00164                                 nu->twist.linear.z = out[z];
00165 
00166                                 return nu;
00167                         }
00168 
00169                         void initialize_controller()
00170                         {
00171                                 ROS_INFO("Initializing dynamic positioning controller...");
00172 
00173                                 ros::NodeHandle nh;
00174                                 Eigen::Vector3d closedLoopFreq(Eigen::Vector3d::Ones());
00175                                 labust::tools::getMatrixParam(nh,"dp_controller/closed_loop_freq", closedLoopFreq);
00176                                 nh.param("dp_controller/sampling",Ts,Ts);
00177 
00178                                 disable_axis[x] = 0;
00179                                 disable_axis[y] = 0;
00180                                 disable_axis[z] = 0;
00181 
00182 
00183                                 enum {Kp=0, Ki, Kd, Kt};
00184                                 for (size_t i=0; i<=2;++i)
00185                                 {
00186                                         PIDBase_init(&con[i]);
00187                                         PIFF_tune(&con[i], float(closedLoopFreq(i)));
00188                                 }
00189 
00190                                 ROS_INFO("Dynamic positioning controller initialized.");
00191                         }
00192 
00193                 private:
00194                         PIDBase con[3];
00195                         double Ts;
00196                 };
00197         }}
00198 
00199 int main(int argc, char* argv[])
00200 {
00201         ros::init(argc,argv,"fadp_3d_control");
00202 
00203         labust::control::HLControl<labust::control::FADPControl,
00204         labust::control::EnableServicePolicy,
00205         labust::control::WindupPolicy<auv_msgs::BodyForceReq> > controller;
00206         ros::spin();
00207 
00208         return 0;
00209 }
00210 
00211 
00212 


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