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
00038
00039
00040
00041
00042
00043 #include <labust/control/esc/EscEKF.hpp>
00044 #include <labust/control/HLControl.hpp>
00045 #include <labust/control/EnablePolicy.hpp>
00046 #include <labust/control/WindupPolicy.hpp>
00047 #include <labust/math/NumberManipulation.hpp>
00048 #include <labust/tools/MatrixLoader.hpp>
00049 #include <labust/tools/conversions.hpp>
00050
00051 #include <Eigen/Dense>
00052 #include <auv_msgs/BodyForceReq.h>
00053 #include <std_msgs/Float32.h>
00054 #include <ros/ros.h>
00055
00056 namespace labust{
00057 namespace control{
00058
00059
00060
00061
00062
00063 struct ESControlEKF_UV : DisableAxis{
00064
00065 enum {x = 0, y};
00066
00067 ESControlEKF_UV():Ts(0.1), esc_controller(2,Ts),count(0),newRange(false), esc_Ts(1.0){};
00068
00069 void init(){
00070
00071 ros::NodeHandle nh;
00072 initialize_controller();
00073 subRange = nh.subscribe<std_msgs::Float32>("range",1,& ESControlEKF_UV::onRange,this);
00074 }
00075
00076 void onRange(const std_msgs::Float32::ConstPtr& msg){
00077 newRange = true;
00078 }
00079
00080 void windup(const auv_msgs::BodyForceReq& tauAch){
00081
00082 };
00083
00084 void idle(const std_msgs::Float32& ref, const auv_msgs::NavSts& state,
00085 const auv_msgs::BodyVelocityReq& track){
00086
00087 };
00088
00089 void reset(const std_msgs::Float32& ref, const auv_msgs::NavSts& state){
00090
00091 };
00092
00093 auv_msgs::BodyVelocityReqPtr step(const std_msgs::Float32& ref, const auv_msgs::NavSts& state){
00094
00095
00096 int t_step = esc_Ts/Ts;
00097
00098 if((count++)%t_step == 0){
00099
00100 newRange = false;
00101
00102 Eigen::Vector2d out, in;
00103 Eigen::Matrix2d R;
00104
00105 Eigen::VectorXd input(2);
00106 input << state.position.north, state.position.east;
00107
00108 in = esc_controller.step(ref.data, input);
00109
00110 auv_msgs::BodyVelocityReqPtr nu(new auv_msgs::BodyVelocityReq());
00111 nu->header.stamp = ros::Time::now();
00112 nu->goal.requester = "esc_ekf_controller";
00113 labust::tools::vectorToDisableAxis(disable_axis, nu->disable_axis);
00114
00115 double yaw = state.orientation.yaw;
00116 R<<cos(yaw),-sin(yaw),sin(yaw),cos(yaw);
00117 out = R.transpose()*in;
00118
00119 nu->twist.linear.x = out[x];
00120 nu->twist.linear.y = out[y];
00121
00122 nu_past = nu;
00123 return nu;
00124 }else{
00125
00126 ROS_ERROR("PAST");
00127 return nu_past;
00128 }
00129 }
00130
00131 void initialize_controller(){
00132
00133 ROS_INFO("Initializing extremum seeking controller...");
00134
00135 ros::NodeHandle nh;
00136
00137 double sin_amp = 0.25;
00138 double sin_freq = 0.09;
00139 double corr_gain = -0.075;
00140 double high_pass_pole = 3;
00141 double low_pass_pole = 0;
00142 double comp_zero = 0;
00143 double comp_pole = 0;
00144 double sampling_time = 0.1;
00145
00146 std::vector<double> Q, R;
00147 Q.assign(3,1);
00148 R.assign(3,1);
00149
00150 nh.param("esc_ekf/sin_amp", sin_amp, sin_amp);
00151 nh.param("esc_ekf/sin_freq", sin_freq, sin_freq);
00152 nh.param("esc_ekf/corr_gain", corr_gain, corr_gain);
00153 nh.param("esc_ekf/high_pass_pole", high_pass_pole, high_pass_pole);
00154 nh.param("esc_ekf/low_pass_pole", low_pass_pole, low_pass_pole);
00155 nh.param("esc_ekf/comp_zero", comp_zero, comp_zero);
00156 nh.param("esc_ekf/comp_pole", comp_pole, comp_pole);
00157 nh.param("esc_ekf/sampling_time", sampling_time, sampling_time);
00158 nh.param("esc_ekf/Q", Q, Q);
00159 nh.param("esc_ekf/R", R, R);
00160
00161 esc_Ts = sampling_time;
00162
00163 esc::EscEkfGrad::vector Q0(3);
00164 Q0 << Q[0],Q[1],Q[2];
00165 esc::EscEkfGrad::vector R0(3);
00166 R0 << R[0],R[1],R[2];
00167
00168 esc_controller.initController(sin_amp, sin_freq, corr_gain, high_pass_pole, low_pass_pole, comp_zero, comp_pole, sampling_time, Q0, R0);
00169
00170 disable_axis[x] = 0;
00171 disable_axis[y] = 0;
00172
00173 ROS_INFO("Extremum seeking controller initialized.");
00174 }
00175
00176 private:
00177
00178 double Ts;
00179 esc::EscEkfGrad esc_controller;
00180 auv_msgs::BodyVelocityReqPtr nu_past;
00181 int count;
00182 double esc_Ts;
00183 bool newRange;
00184 ros::Subscriber subRange;
00185
00186 };
00187 }
00188 }
00189
00190 int main(int argc, char* argv[])
00191 {
00192 ros::init(argc,argv,"esc_classic_control");
00193
00194
00195
00196
00197
00198
00199
00200
00201
00202
00203
00204
00205 labust::control::HLControl<labust::control::ESControlEKF_UV,
00206 labust::control::EnableServicePolicy,
00207 labust::control::NoWindup,
00208 auv_msgs::BodyVelocityReq,
00209 auv_msgs::NavSts,
00210 std_msgs::Float32> controller;
00211 ros::spin();
00212
00213 return 0;
00214 }
00215
00216
00217