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 ALTControl : DisableAxis
00058 {
00059 ALTControl():Ts(0.1),manRefFlag(true),depth_threshold(0.1),depth_timeout(10){};
00060
00061 void init()
00062 {
00063 ros::NodeHandle nh;
00064 manRefSub = nh.subscribe<std_msgs::Bool>("manRefAltitude",1,&ALTControl::onManRef,this);
00065 initialize_controller();
00066 }
00067
00068 void onManRef(const std_msgs::Bool::ConstPtr& state)
00069 {
00070 manRefFlag = state->data;
00071 }
00072 void windup(const auv_msgs::BodyForceReq& tauAch)
00073 {
00074
00075 con.extWindup = tauAch.windup.z;
00076 };
00077
00078 void idle(const auv_msgs::NavSts& ref, const auv_msgs::NavSts& state,
00079 const auv_msgs::BodyVelocityReq& track)
00080 {
00081
00082 con.desired = state.altitude;
00083 con.state = state.altitude;
00084 con.track = -track.twist.linear.z;
00085 PIFF_ffIdle(&con, Ts, -ref.body_velocity.z);
00086 };
00087
00088 void reset(const auv_msgs::NavSts& ref, const auv_msgs::NavSts& state)
00089 {
00090
00091 };
00092
00093 auv_msgs::BodyVelocityReqPtr step(const auv_msgs::NavSts& ref,
00094 const auv_msgs::NavSts& state)
00095 {
00096 con.desired = ref.altitude;
00097 con.state = state.altitude;
00098 con.track = -state.body_velocity.z;
00099
00100 double tmp_output;
00101 auv_msgs::BodyVelocityReqPtr nu(new auv_msgs::BodyVelocityReq());
00102
00103 if(manRefFlag)
00104 {
00105 if (state.position.depth > depth_threshold) underwater_time = ros::Time::now();
00106
00107 if (((ros::Time::now() - underwater_time).toSec() > depth_timeout))
00108 {
00109 PIFF_ffIdle(&con, Ts, 0);
00110 tmp_output = 0;
00111 }
00112 else
00113 {
00114
00115 PIFF_ffStep(&con, Ts, 0*(-1)*ref.body_velocity.z);
00116 tmp_output = -con.output;
00117 }
00118
00119
00120 }
00121 else
00122 {
00123 PIFF_ffIdle(&con, Ts, -ref.body_velocity.z);
00124 tmp_output = ref.body_velocity.z;
00125 }
00126
00127 nu->header.stamp = ros::Time::now();
00128 nu->goal.requester = "alt_controller";
00129 labust::tools::vectorToDisableAxis(disable_axis, nu->disable_axis);
00130
00131 nu->twist.linear.z = tmp_output;
00132
00133 return nu;
00134 }
00135
00136 void initialize_controller()
00137 {
00138 ROS_INFO("Initializing altitude controller...");
00139
00140 ros::NodeHandle nh;
00141 double closedLoopFreq(1);
00142 nh.param("alt_controller/closed_loop_freq", closedLoopFreq, closedLoopFreq);
00143 nh.param("alt_controller/sampling",Ts,Ts);
00144 nh.param("depth_controller/depth_threshold",depth_threshold,depth_threshold);
00145 nh.param("depth_controller/depth_timeout",depth_timeout,depth_timeout);
00146
00147 disable_axis[2] = 0;
00148
00149 PIDBase_init(&con);
00150 PIFF_tune(&con, float(closedLoopFreq));
00151
00152 ROS_INFO("Altitude controller initialized.");
00153 }
00154
00155 private:
00156 ros::Subscriber alt_sub;
00157 PIDBase con;
00158 double Ts;
00159 double depth_threshold;
00160 double depth_timeout;
00161 ros::Time underwater_time;
00162 ros::Subscriber manRefSub;
00163 bool manRefFlag;
00164 };
00165 }
00166 }
00167
00168 int main(int argc, char* argv[])
00169 {
00170 ros::init(argc,argv,"alt_control");
00171
00172 labust::control::HLControl<labust::control::ALTControl,
00173 labust::control::EnableServicePolicy,
00174 labust::control::WindupPolicy<auv_msgs::BodyForceReq> > controller;
00175
00176 ros::spin();
00177
00178 return 0;
00179 }
00180
00181
00182