HLControl.hpp
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  *  Created on: 26.06.2013.
00035  *  Author: Dula Nad
00036  *********************************************************************/
00037 #ifndef HLCONTROL_HPP_
00038 #define HLCONTROL_HPP_
00039 #include <auv_msgs/NavSts.h>
00040 #include <auv_msgs/BodyVelocityReq.h>
00041 #include <navcon_msgs/ConfigureAxes.h>
00042 #include <ros/ros.h>
00043 
00044 #include <boost/thread/mutex.hpp>
00045 
00046 namespace labust
00047 {
00048         namespace control
00049         {
00050                 struct NoEnable{static const bool enable=true;};
00051                 struct NoWindup{
00052                         template <class Base>
00053                         inline void get_windup(Base b){};
00054                 };
00055 
00056                 struct DisableAxis
00057                 {
00058                         DisableAxis()
00059                         {
00060                                 for (int i=0; i<6; ++i) disable_axis[i]=1;
00061                         }
00062                         bool disable_axis[6];
00063                 };
00064 
00066                 class ConfigureAxesPolicy
00067                 {
00068                 public:
00069                         ConfigureAxesPolicy()
00070                         {
00071                                 ros::NodeHandle nh;
00072                                 configureAxes = nh.advertiseService("ConfigureAxes",
00073                                                 &ConfigureAxesPolicy::onConfiguration, this);
00074                         }
00075 
00076                         bool onConfiguration(navcon_msgs::ConfigureAxes::Request& req,
00077                                         navcon_msgs::ConfigureAxes::Response& resp)
00078                         {
00079                                 this->disable_axis = req.disable_axis;
00080                                 return true;
00081                         }
00082 
00083                 protected:
00087                         auv_msgs::Bool6Axis disable_axis;
00091                         ros::ServiceServer configureAxes;
00092                 };
00093 
00099                 template <
00100                 class Controller,
00101                 class Enable = NoEnable,
00102                 class Windup = NoWindup,
00103                 class OutputType = auv_msgs::BodyVelocityReq,
00104                 class InputType = auv_msgs::NavSts,
00105                 class ReferenceType = auv_msgs::NavSts
00106                 >
00107                 class HLControl : public Controller, Enable, Windup
00108                 {
00109                 public:
00113                         HLControl()
00114                         {
00115                                 onInit();
00116                         }
00120                         void onInit()
00121                         {
00122                                 ros::NodeHandle nh;
00123                                 //Initialize publishers
00124                                 outPub = nh.advertise<OutputType>("out", 1);
00125 
00126                                 //Initialize subscribers
00127                                 stateSub = nh.subscribe<InputType>("state", 1,
00128                                                 &HLControl::onEstimate,this);
00129                                 trackState = nh.subscribe<ReferenceType>("ref", 1,
00130                                                 &HLControl::onRef,this);
00131 
00132                                 Controller::init();
00133                         }
00134 
00135                 private:
00136 
00137                         void onRef(const typename ReferenceType::ConstPtr& ref)
00138                         {
00139                                 boost::mutex::scoped_lock l(cnt_mux);
00140                                 this->ref = *ref;
00141                         }
00142 
00143                         void onEstimate(const typename InputType::ConstPtr& estimate)
00144                         {
00145                                 if (!Enable::enable)
00146                                 {
00147                                         lastEn = false;
00148                                         return;
00149                                 }
00150 
00151                                 //Copy into controller
00152                                 Windup::get_windup(this);
00153                                 boost::mutex::scoped_lock l(cnt_mux);
00154                                 if (Enable::enable && !lastEn)
00155                                 {
00156                                         this->reset(ref, *estimate);
00157                                         lastEn = true;
00158                                 }
00159                                 outPub.publish(Controller::step(ref, *estimate));
00160                         }
00161 
00165                         ros::Publisher outPub;
00169                         ros::Subscriber stateSub, trackState;
00173                         ReferenceType ref;
00177                         bool disabled_axis[6], lastEn;
00181                         boost::mutex cnt_mux;
00182                 };
00183         }
00184 }
00185 
00186 /* HLCONTROL_HPP_ */
00187 #endif


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