HDGControlDirect.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/PIDFFController.h>
00041 #include <labust/control/IPDFFController.h>
00042 #include <labust/simulation/DynamicsParams.hpp>
00043 #include <labust/tools/DynamicsLoader.hpp>
00044 #include <labust/math/NumberManipulation.hpp>
00045 #include <labust/tools/MatrixLoader.hpp>
00046 #include <labust/tools/conversions.hpp>
00047 
00048 #include <Eigen/Dense>
00049 #include <auv_msgs/BodyForceReq.h>
00050 #include <ros/ros.h>
00051 
00052 namespace labust
00053 {
00054         namespace control{
00056                 struct HDGControlDirect : DisableAxis
00057                 {
00058                         enum {x=0,y};
00059 
00060                         HDGControlDirect():Ts(0.1),useIP(false){};
00061 
00062                         void init()
00063                         {
00064                                 ros::NodeHandle nh;
00065                                 initialize_controller();
00066                         }
00067 
00068                 void windup(const auv_msgs::BodyForceReq& tauAch)
00069                         {
00070                                 //Copy into controller
00071                                 //con.windup = tauAch.disable_axis.yaw;
00072                         };
00073 
00074                 void reset(const auv_msgs::NavSts& ref, const auv_msgs::NavSts& state)
00075                 {
00076                         con.internalState = 0;
00077                         con.lastState = useIP?unwrap(state.orientation.yaw):state.orientation.yaw;
00078                 };
00079 
00080                         auv_msgs::BodyForceReqPtr step(const auv_msgs::NavSts& ref,
00081                                         const auv_msgs::NavSts& state)
00082                         {
00083                                 con.desired = ref.orientation.yaw;
00084                                 con.state = (useIP?unwrap(state.orientation.yaw):state.orientation.yaw);
00085 
00086                                 float errorWrap = labust::math::wrapRad(
00087                                         con.desired - con.state);
00088                                 //Zero feed-forward
00089                                 if (useIP)
00090                                 {
00091                                         IPDFF_dwffStep(&con,Ts, errorWrap, 0, state.orientation_rate.yaw);
00092                                 }
00093                                 else
00094                                 {
00095                                         PIDFF_wffStep(&con,Ts, errorWrap, 0);
00096                                 }
00097 
00098                                 auv_msgs::BodyForceReqPtr nu(new auv_msgs::BodyForceReq());
00099                                 nu->header.stamp = ros::Time::now();
00100                                 nu->goal.requester = "hdg_controller_direct";
00101                                 labust::tools::vectorToDisableAxis(disable_axis, nu->disable_axis);
00102 
00103                                 nu->wrench.torque.z = con.output;
00104 
00105                                 ROS_INFO("Current PID state: windup=%d, out=%f, out_c=%f, error=%f",con.windup, con.internalState, con.output,errorWrap);
00106 
00107                                 return nu;
00108                         }
00109 
00110                         void initialize_controller()
00111                         {
00112                                 ROS_INFO("Initializing heading controller direct...");
00113 
00114                                 ros::NodeHandle nh;
00115                                 labust::simulation::DynamicsParams model;
00116                                 labust::tools::loadDynamicsParams(nh,model);
00117 
00118                                 double closedLoopFreq(1), max(100);
00119                                 nh.param("hdg_controller/closed_loop_freq", closedLoopFreq, closedLoopFreq);
00120                                 nh.param("hdg_controller/sampling",Ts,Ts);
00121                                 nh.param("hdg_controller/use_ip",useIP,useIP);
00122                                 nh.param("hdg_controller/max_n",max,max);
00123 
00124                                 disable_axis[5] = 0;
00125 
00126                                 PT1Model m;
00127                                 m.alpha = model.Io(2,2) + model.Ma(2,2);
00128                                 m.beta = model.Dlin(5,5);
00129 
00130                                 PIDBase_init(&con);
00131                                 //PIFF_tune(&con, float(closedLoopFreq));
00132                                 PIDFF_modelTune(&con, &m, float(closedLoopFreq));
00133                                 con.autoWindup=1;
00134                                 con.outputLimit = max;
00135 
00136                                 ROS_INFO("Heading controller direct initialized.");
00137                         }
00138 
00139                 private:
00140                         ros::Subscriber alt_sub;
00141                         PIDBase con;
00142                         double Ts;
00143                         bool useIP;
00144                         labust::math::unwrap unwrap;
00145                 };
00146         }}
00147 
00148 int main(int argc, char* argv[])
00149 {
00150         ros::init(argc,argv,"hdg_control");
00151 
00152         labust::control::HLControl<labust::control::HDGControlDirect,
00153         labust::control::EnableServicePolicy,
00154         labust::control::NoWindup,
00155         auv_msgs::BodyForceReq > controller;
00156         ros::spin();
00157 
00158         return 0;
00159 }
00160 
00161 
00162 


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