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/math/NumberManipulation.hpp>
00043 #include <labust/tools/MatrixLoader.hpp>
00044 #include <labust/tools/conversions.hpp>
00045
00046 #include <Eigen/Dense>
00047 #include <auv_msgs/BodyForceReq.h>
00048 #include <std_msgs/Float32.h>
00049 #include <ros/ros.h>
00050
00051 namespace labust
00052 {
00053 namespace control{
00055 struct ALTControl : DisableAxis
00056 {
00057 enum {x=0,y};
00058
00059 ALTControl():Ts(0.1), useIP(false), minAltitude(5){};
00060
00061 void init()
00062 {
00063 ros::NodeHandle nh;
00064 initialize_controller();
00065 }
00066
00067 void windup(const auv_msgs::BodyForceReq& tauAch)
00068 {
00069
00070
00071 con.extWindup = tauAch.windup.z;
00072 };
00073
00074 void reset(const auv_msgs::NavSts& ref, const auv_msgs::NavSts& state)
00075 {
00076 con.internalState = 0;
00077 lastRef = ref.position.depth;
00078 if (ref.position.depth < 0)
00079 {
00080 con.lastState = state.altitude;
00081 }
00082 else
00083 {
00084 con.lastState = state.position.depth;
00085 }
00086 };
00087
00088 auv_msgs::BodyVelocityReqPtr step(const auv_msgs::NavSts& ref,
00089 const auv_msgs::NavSts& state)
00090 {
00091 con.desired = ref.position.depth;
00092
00093
00094 if ((lastRef > 0) && (ref.position.depth < 0))
00095 {
00096 con.lastState = state.altitude;
00097 con.lastRef = -ref.position.depth;
00098 }
00099 else if ((lastRef < 0) && (ref.position.depth > 0))
00100 {
00101 con.lastState = state.position.depth;
00102 con.lastRef = ref.position.depth;
00103 }
00104 lastRef = ref.position.depth;
00105
00106
00107 float wd = state.body_velocity.z;
00108 if (ref.position.depth < 0)
00109 {
00110
00111 con.desired = -ref.position.depth;
00112 con.state = state.altitude;
00113
00114 wd = -wd;
00115 }
00116 else
00117 {
00118
00119 con.state = state.position.depth;
00120 }
00121
00122
00123
00124
00125 if (useIP)
00126 {
00127 IPFF_ffStep(&con, Ts, ref.body_velocity.z);
00128 ROS_INFO("Current state=%f, desired=%f, windup=%d", con.state, con.desired, con.windup);
00129 }
00130 else
00131 {
00132 PSatD_dStep(&con, Ts, 0);
00133 ROS_INFO("Current state=%f, desired=%f", con.state, con.desired);
00134 }
00135
00136 auv_msgs::BodyVelocityReqPtr nu(new auv_msgs::BodyVelocityReq());
00137 nu->header.stamp = ros::Time::now();
00138 nu->goal.requester = "alt_controller";
00139 labust::tools::vectorToDisableAxis(disable_axis, nu->disable_axis);
00140
00141 if (ref.position.depth < 0)
00142 {
00143 nu->twist.linear.z = -con.output;
00144 }
00145 else
00146 {
00147 nu->twist.linear.z = con.output;
00148 }
00149
00150
00151 if (state.altitude < minAltitude)
00152 {
00153 con.internalState = 0;
00154 nu->twist.linear.z = 0;
00155 }
00156
00157 return nu;
00158 }
00159
00160 void initialize_controller()
00161 {
00162 ROS_INFO("Initializing depth/altitude controller...");
00163
00164 ros::NodeHandle nh;
00165 double closedLoopFreq(1);
00166 nh.param("alt_controller/closed_loop_freq", closedLoopFreq, closedLoopFreq);
00167 nh.param("alt_controller/sampling",Ts,Ts);
00168 nh.param("alt_controller/use_ip",useIP,useIP);
00169 nh.param("alt_controller/min_altitude",minAltitude,minAltitude);
00170
00171 disable_axis[2] = 0;
00172
00173 PIDBase_init(&con);
00174
00175 if (useIP)
00176 {
00177 IPFF_tune(&con, float(closedLoopFreq));
00178 }
00179 else
00180 {
00181 PSatD_tune(&con, float(closedLoopFreq), 0, 1);
00182 con.outputLimit = 1;
00183 }
00184
00185 ROS_INFO("Depth/Altitude controller initialized.");
00186 }
00187
00188 private:
00189 ros::Subscriber alt_sub;
00190 PIDBase con;
00191 double Ts;
00192 bool useIP;
00193 double lastRef;
00194 double minAltitude;
00195 };
00196 }}
00197
00198 int main(int argc, char* argv[])
00199 {
00200 ros::init(argc,argv,"alt_control");
00201
00202 labust::control::HLControl<labust::control::ALTControl,
00203 labust::control::EnableServicePolicy,
00204 labust::control::WindupPolicy<auv_msgs::BodyForceReq> > controller;
00205
00206 ros::spin();
00207
00208 return 0;
00209 }
00210
00211
00212