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 #include <labust/control/HLControl.hpp>
00038 #include <labust/control/EnablePolicy.hpp>
00039 #include <labust/control/WindupPolicy.hpp>
00040 #include <labust/control/PSatDController.h>
00041 #include <labust/control/IPFFController.h>
00042 #include <labust/control/PIFFController.h>
00043 #include <labust/math/NumberManipulation.hpp>
00044 #include <labust/tools/MatrixLoader.hpp>
00045 #include <labust/tools/conversions.hpp>
00046
00047 #include <Eigen/Dense>
00048 #include <auv_msgs/BodyForceReq.h>
00049 #include <std_msgs/Float32.h>
00050 #include <std_msgs/Bool.h>
00051 #include <ros/ros.h>
00052
00053 namespace labust
00054 {
00055 namespace control{
00057 struct DepthControl : DisableAxis
00058 {
00059 DepthControl():Ts(0.1),manRefFlag(true){};
00060
00061 void init()
00062 {
00063 ros::NodeHandle nh;
00064 manRefSub = nh.subscribe<std_msgs::Bool>("manRefDepthPosition",1,&DepthControl::onManRef,this);
00065 initialize_controller();
00066 }
00067
00068 void onManRef(const std_msgs::Bool::ConstPtr& state)
00069 {
00070 manRefFlag = state->data;
00071 }
00072
00073
00074 void windup(const auv_msgs::BodyForceReq& tauAch)
00075 {
00076
00077 con.extWindup = tauAch.windup.z;
00078 };
00079
00080 void idle(const auv_msgs::NavSts& ref, const auv_msgs::NavSts& state,
00081 const auv_msgs::BodyVelocityReq& track)
00082 {
00083
00084 con.desired = state.position.depth;
00085 con.state = state.position.depth;
00086 con.track = track.twist.linear.z;
00087 con.track = state.body_velocity.z;
00088 PIFF_idle(&con, Ts);
00089 };
00090
00091 void reset(const auv_msgs::NavSts& ref, const auv_msgs::NavSts& state)
00092 {
00093
00094 };
00095
00096 auv_msgs::BodyVelocityReqPtr step(const auv_msgs::NavSts& ref,
00097 const auv_msgs::NavSts& state)
00098 {
00099 con.desired = ref.position.depth;
00100 con.state = state.position.depth;
00101 con.track = state.body_velocity.z;
00102
00103 double tmp_output;
00104 auv_msgs::BodyVelocityReqPtr nu(new auv_msgs::BodyVelocityReq());
00105
00106 if(manRefFlag)
00107 {
00108 if (state.position.depth > depth_threshold)
00109 {
00110 ROS_ERROR("Underwater");
00111 underwater_time = ros::Time::now();
00112 }
00113
00114 if (((ros::Time::now() - underwater_time).toSec() > depth_timeout) &&
00115 ref.position.depth < depth_threshold)
00116 {
00117 PIFF_ffIdle(&con, Ts, 0);
00118 ROS_ERROR("Surface");
00119 tmp_output = 0;
00120 }
00121 else
00122 {
00123
00124 ROS_ERROR("working");
00125 PIFF_ffStep(&con, Ts, 0*ref.body_velocity.z);
00126 tmp_output = con.output;
00127 }
00128
00129 }
00130 else
00131 {
00132 PIFF_idle(&con, Ts);
00133 tmp_output = ref.body_velocity.z;
00134 }
00135
00136 nu->header.stamp = ros::Time::now();
00137 nu->goal.requester = "depth_controller";
00138 labust::tools::vectorToDisableAxis(disable_axis, nu->disable_axis);
00139
00140 nu->twist.linear.z = tmp_output;
00141
00142 return nu;
00143 }
00144
00145 void initialize_controller()
00146 {
00147 ROS_INFO("Initializing depth controller...");
00148
00149 ros::NodeHandle nh;
00150 double closedLoopFreq(1);
00151 nh.param("depth_controller/closed_loop_freq", closedLoopFreq, closedLoopFreq);
00152 nh.param("depth_controller/sampling",Ts,Ts);
00153 nh.param("depth_controller/depth_threshold",depth_threshold,depth_threshold);
00154 nh.param("depth_controller/depth_timeout",depth_timeout,depth_timeout);
00155
00156
00157 disable_axis[2] = 0;
00158
00159 PIDBase_init(&con);
00160 PIFF_tune(&con, float(closedLoopFreq));
00161
00162 ROS_INFO("Depth controller initialized.");
00163 }
00164
00165 private:
00166 PIDBase con;
00167 double Ts;
00168 double depth_threshold;
00169 double depth_timeout;
00170 ros::Time underwater_time;
00171 ros::Subscriber manRefSub;
00172 bool manRefFlag;
00173 };
00174 }}
00175
00176 int main(int argc, char* argv[])
00177 {
00178 ros::init(argc,argv,"Depth_control");
00179
00180 labust::control::HLControl<labust::control::DepthControl,
00181 labust::control::EnableServicePolicy,
00182 labust::control::WindupPolicy<auv_msgs::BodyForceReq> > controller;
00183
00184 ros::spin();
00185
00186 return 0;
00187 }
00188
00189
00190