Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
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
00100 template <
00101 class Controller,
00102 class Enable = NoEnable,
00103 class Windup = NoWindup,
00104 class OutputType = auv_msgs::BodyVelocityReq,
00105 class InputType = auv_msgs::NavSts,
00106 class ReferenceType = auv_msgs::NavSts
00107 >
00108 class HLControl : public Controller, Enable, Windup
00109 {
00110 enum {TIMEOUT=2};
00111 public:
00115 HLControl():
00116 lastEn(false),
00117 refOk(false)
00118 {
00119 onInit();
00120 }
00124 void onInit()
00125 {
00126 ros::NodeHandle nh;
00127
00128 outPub = nh.advertise<OutputType>("out", 1);
00129
00130
00131 stateSub = nh.subscribe<InputType>("state", 1,
00132 &HLControl::onEstimate,this);
00133 trackState = nh.subscribe<ReferenceType>("ref", 1,
00134 &HLControl::onRef,this);
00135 extSub = nh.subscribe<OutputType>("track", 1,
00136 &HLControl::onTrack,this);
00137
00138 Controller::init();
00139 }
00140
00141 private:
00142
00143 void onRef(const typename ReferenceType::ConstPtr& ref)
00144 {
00145 boost::mutex::scoped_lock l(cnt_mux);
00146 refOk = true;
00147 this->ref = *ref;
00148 }
00149
00150 void onTrack(const typename OutputType::ConstPtr& ext)
00151 {
00152 boost::mutex::scoped_lock l(cnt_mux);
00153 this->ext = *ext;
00154 }
00155
00156 void onEstimate(const typename InputType::ConstPtr& estimate)
00157 {
00158 if (!Enable::enable)
00159 {
00160 this->idle(ref, *estimate, ext);
00161 lastEn = false;
00162 refOk = false;
00163 return;
00164 }
00165
00166 if (!refOk) return;
00167
00168
00169 Windup::get_windup(this);
00170 boost::mutex::scoped_lock l(cnt_mux);
00171 if (Enable::enable && !lastEn)
00172 {
00173
00174 lastEn = true;
00175 }
00176 outPub.publish(Controller::step(ref, *estimate));
00177 }
00178
00182 ros::Publisher outPub;
00186 ros::Subscriber stateSub, trackState, extSub;
00190 ReferenceType ref;
00192 OutputType ext;
00196 bool disabled_axis[6], lastEn, refOk;
00200 boost::mutex cnt_mux;
00201 };
00202 }
00203 }
00204
00205
00206 #endif