HDGControl.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/PIFFController.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 <ros/ros.h>
00049 
00050 namespace labust
00051 {
00052         namespace control{
00054                 struct HDGControl : DisableAxis
00055                 {
00056                         enum {x=0,y};
00057 
00058                         HDGControl():Ts(0.1),useIP(false){};
00059 
00060                         void init()
00061                         {
00062                                 ros::NodeHandle nh;
00063                                 initialize_controller();
00064                         }
00065 
00066                 void windup(const auv_msgs::BodyForceReq& tauAch)
00067                         {
00068                                 //Copy into controller
00069                                 con.windup = tauAch.disable_axis.yaw;
00070                         };
00071 
00072                 void reset(const auv_msgs::NavSts& ref, const auv_msgs::NavSts& state)
00073                 {
00074                         con.internalState = 0;
00075                         con.lastState = useIP?unwrap(state.orientation.yaw):state.orientation.yaw;
00076                 };
00077 
00078                         auv_msgs::BodyVelocityReqPtr step(const auv_msgs::NavSts& ref,
00079                                         const auv_msgs::NavSts& state)
00080                         {
00081                                 con.desired = ref.orientation.yaw;
00082                                 con.state = (useIP?unwrap(state.orientation.yaw):state.orientation.yaw);
00083 
00084                                 float errorWrap = labust::math::wrapRad(
00085                                         con.desired - con.state);
00086                                 //Zero feed-forward
00087                                 if (useIP)
00088                                 {
00089                                         IPFF_wffStep(&con,Ts, errorWrap, 0);
00090                                 }
00091                                 else
00092                                 {
00093                                         PIFF_wffStep(&con,Ts, errorWrap, 0);
00094                                 }
00095 
00096                                 auv_msgs::BodyVelocityReqPtr nu(new auv_msgs::BodyVelocityReq());
00097                                 nu->header.stamp = ros::Time::now();
00098                                 nu->goal.requester = "hdg_controller";
00099                                 labust::tools::vectorToDisableAxis(disable_axis, nu->disable_axis);
00100 
00101                                 nu->twist.angular.z = con.output;
00102 
00103                                 return nu;
00104                         }
00105 
00106                         void initialize_controller()
00107                         {
00108                                 ROS_INFO("Initializing heading controller...");
00109 
00110                                 ros::NodeHandle nh;
00111                                 double closedLoopFreq(1);
00112                                 nh.param("hdg_controller/closed_loop_freq", closedLoopFreq, closedLoopFreq);
00113                                 nh.param("hdg_controller/sampling",Ts,Ts);
00114                                 nh.param("hdg_controller/use_ip",useIP,useIP);
00115 
00116                                 disable_axis[5] = 0;
00117 
00118                                 PIDBase_init(&con);
00119                                 PIFF_tune(&con, float(closedLoopFreq));
00120 
00121                                 ROS_INFO("Heading controller initialized.");
00122                         }
00123 
00124                 private:
00125                         ros::Subscriber alt_sub;
00126                         PIDBase con;
00127                         double Ts;
00128                         bool useIP;
00129                         labust::math::unwrap unwrap;
00130                 };
00131         }}
00132 
00133 int main(int argc, char* argv[])
00134 {
00135         ros::init(argc,argv,"hdg_control");
00136 
00137         labust::control::HLControl<labust::control::HDGControl,
00138         labust::control::EnableServicePolicy,
00139         labust::control::WindupPolicy<auv_msgs::BodyForceReq> > controller;
00140         ros::spin();
00141 
00142         return 0;
00143 }
00144 
00145 
00146 


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