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/EscClassic.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 ESCControlClassic_UV : DisableAxis{
00064
00065 enum {x = 0, y};
00066
00067 ESCControlClassic_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,& ESCControlClassic_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
00106 in = esc_controller.step(ref.data);
00107
00108 ROS_ERROR("cost:");
00109 ROS_ERROR_STREAM(ref.data);
00110 ROS_ERROR("control:");
00111 ROS_ERROR_STREAM(in);
00112
00113
00114 auv_msgs::BodyVelocityReqPtr nu(new auv_msgs::BodyVelocityReq());
00115 nu->header.stamp = ros::Time::now();
00116 nu->goal.requester = "esc_controller";
00117 labust::tools::vectorToDisableAxis(disable_axis, nu->disable_axis);
00118
00119 double yaw = state.orientation.yaw;
00120 R<<cos(yaw),-sin(yaw),sin(yaw),cos(yaw);
00121 out = R.transpose()*in;
00122
00123 nu->twist.linear.x = out[x];
00124 nu->twist.linear.y = out[y];
00125
00126 nu_past = nu;
00127 return nu;
00128 }else{
00129
00130 ROS_ERROR("PAST");
00131 return nu_past;
00132 }
00133 }
00134
00135 void initialize_controller(){
00136
00137 ROS_INFO("Initializing extremum seeking controller...");
00138
00139 ros::NodeHandle nh;
00140
00141 double sin_amp = 0.2;
00142 double sin_freq = 0.09;
00143 double corr_gain = -5;
00144 double high_pass_pole = 3;
00145 double low_pass_pole = 0;
00146 double comp_zero = 0;
00147 double comp_pole = 0;
00148 double sampling_time = 0.1;
00149
00150 nh.param("esc/sin_amp", sin_amp, sin_amp);
00151 nh.param("esc/sin_freq", sin_freq, sin_freq);
00152 nh.param("esc/corr_gain", corr_gain, corr_gain);
00153 nh.param("esc/high_pass_pole", high_pass_pole, high_pass_pole);
00154 nh.param("esc/low_pass_pole", low_pass_pole, low_pass_pole);
00155 nh.param("esc/comp_zero", comp_zero, comp_zero);
00156 nh.param("esc/comp_pole", comp_pole, comp_pole);
00157 nh.param("esc/sampling_time", sampling_time, sampling_time);
00158
00159 esc_Ts = sampling_time;
00160
00161 esc_controller.initController(sin_amp, sin_freq, corr_gain, high_pass_pole, low_pass_pole, comp_zero, comp_pole, sampling_time);
00162
00163 disable_axis[x] = 0;
00164 disable_axis[y] = 0;
00165
00166 ROS_INFO("Extremum seeking controller initialized.");
00167 }
00168
00169 private:
00170
00171 double Ts;
00172 esc::EscClassic esc_controller;
00173 auv_msgs::BodyVelocityReqPtr nu_past;
00174 int count;
00175 double esc_Ts;
00176 bool newRange;
00177 ros::Subscriber subRange;
00178
00179 };
00180 }
00181 }
00182
00183 int main(int argc, char* argv[])
00184 {
00185 ros::init(argc,argv,"esc_classic_control");
00186
00187
00188
00189
00190
00191
00192
00193
00194
00195
00196
00197
00198 labust::control::HLControl<labust::control::ESCControlClassic_UV,
00199 labust::control::EnableServicePolicy,
00200 labust::control::NoWindup,
00201 auv_msgs::BodyVelocityReq,
00202 auv_msgs::NavSts,
00203 std_msgs::Float32> controller;
00204 ros::spin();
00205
00206 return 0;
00207 }
00208
00209
00210