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 <labust_uvapp/EnableControl.h>
00040
00041 #include <auv_msgs/NavSts.h>
00042 #include <auv_msgs/BodyForceReq.h>
00043 #include <auv_msgs/BodyVelocityReq.h>
00044 #include <geometry_msgs/PointStamped.h>
00045 #include <std_msgs/Float32.h>
00046 #include <std_msgs/Bool.h>
00047 #include <ros/ros.h>
00048
00049 namespace labust
00050 {
00051 namespace control
00052 {
00056 class WindupPolicy
00057 {
00058 public:
00059 WindupPolicy()
00060 {
00061 ros::NodeHandle nh;
00062 windupSub = nh.subscribe<auv_msgs::BodyForceReq>("tauAch", 1,
00063 &WindupPolicy::onWindup,this);
00064 }
00065
00066 void onWindup(const auv_msgs::BodyForceReq::ConstPtr& tauAch)
00067 {
00068 ROS_INFO("Handle windup policy.");
00069 this->tauAch = *tauAch;
00070 }
00071
00072 template <class Base>
00073 inline void get_windup(Base* b){b->windup(tauAch);};
00074
00075 protected:
00076 ros::Subscriber windupSub;
00077 auv_msgs::BodyForceReq tauAch;
00078 };
00079
00080 class EnablePolicy
00081 {
00082 public:
00083 EnablePolicy():
00084 enable(false)
00085 {
00086 ros::NodeHandle nh;
00087 enableControl = nh.advertiseService("Enable",
00088 &EnablePolicy::onEnableControl, this);
00089 }
00090
00091 bool onEnableControl(labust_uvapp::EnableControl::Request& req,
00092 labust_uvapp::EnableControl::Response& resp)
00093 {
00094 this->enable = req.enable;
00095 return true;
00096 }
00097
00098 protected:
00102 bool enable;
00106 ros::ServiceServer enableControl;
00107 };
00108
00109 struct NoEnable{static const bool enable=true;};
00110 struct NoWindup{
00111 template <class Base>
00112 inline void get_windup(Base b){};};
00113
00119 template <
00120 class Controller,
00121 class Enable = NoEnable,
00122 class Windup = NoWindup,
00123 class OutputType = auv_msgs::BodyVelocityReq,
00124 class InputType = auv_msgs::NavSts
00125 >
00126 class HLControl : public Controller, Enable, Windup
00127 {
00128 public:
00132 HLControl()
00133 {
00134 onInit();
00135 }
00139 void onInit()
00140 {
00141 ros::NodeHandle nh;
00142
00143 refPub = nh.advertise<OutputType>("ref", 1);
00144
00145
00146 stateSub = nh.subscribe<InputType>("state", 1,
00147 &HLControl::onEstimate,this);
00148
00149 Controller::init();
00150 }
00151
00152 private:
00153
00154 void onEstimate(const typename InputType::ConstPtr& estimate)
00155 {
00156 if (!Enable::enable) return;
00157
00158 typename OutputType::Ptr ref(new OutputType());
00159 Windup::get_windup(this);
00160 Controller::step(estimate, ref);
00161 refPub.publish(ref);
00162 }
00163
00167 ros::Publisher refPub;
00171 ros::Subscriber stateSub;
00172 };
00173 }
00174 }
00175
00176
00177 #endif