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
00038
00039
00040
00041
00042
00043 #include <labust/control/esc/EscBounded.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 ESCControlBounded_UV : DisableAxis{
00064
00065 enum {x = 0, y};
00066
00067 ESCControlBounded_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,& ESCControlBounded_UV::onRange,this);
00074
00075 }
00076
00077 void onRange(const std_msgs::Float32::ConstPtr& msg){
00078 newRange = true;
00079 }
00080
00081 void windup(const auv_msgs::BodyForceReq& tauAch){
00082
00083 };
00084
00085 void idle(const std_msgs::Float32& ref, const auv_msgs::NavSts& state,
00086 const auv_msgs::BodyVelocityReq& track){
00087
00088 };
00089
00090 void reset(const std_msgs::Float32& ref, const auv_msgs::NavSts& state){
00091
00092 };
00093
00094 auv_msgs::BodyVelocityReqPtr step(const std_msgs::Float32& ref, const auv_msgs::NavSts& state){
00095
00096
00097 int t_step = esc_Ts/Ts;
00098
00099 if((count++)%t_step == 0){
00100
00101 newRange = false;
00102
00103 Eigen::Vector2d out, in;
00104 Eigen::Matrix2d R;
00105
00106 in = esc_controller.step(ref.data);
00107
00108 auv_msgs::BodyVelocityReqPtr nu(new auv_msgs::BodyVelocityReq());
00109 nu->header.stamp = ros::Time::now();
00110 nu->goal.requester = "esc_controller_bounded";
00111 labust::tools::vectorToDisableAxis(disable_axis, nu->disable_axis);
00112
00113 double yaw = state.orientation.yaw;
00114 R<<cos(yaw),-sin(yaw),sin(yaw),cos(yaw);
00115 out = R.transpose()*in;
00116
00117 nu->twist.linear.x = out[x];
00118 nu->twist.linear.y = out[y];
00119
00120 nu_past = nu;
00121 return nu;
00122 }else{
00123
00124 ROS_ERROR("PAST");
00125 return nu_past;
00126 }
00127 }
00128
00129 void initialize_controller(){
00130
00131 ROS_INFO("Initializing extremum seeking controller...");
00132
00133 ros::NodeHandle nh;
00134
00135
00136
00137
00138
00139
00140
00141
00142
00143 double K = 1.1;
00144 double alpha = 0.7;
00145 double omega = 0.3;
00146 double sampling_time = 0.1;
00147
00148 nh.param("esc_bounded/K", K, K);
00149 nh.param("esc_bounded/alpha", alpha, alpha);
00150 nh.param("esc_bounded/omega", omega, omega);
00151 nh.param("esc_bounded/sampling_time", sampling_time, sampling_time);
00152
00153 esc_Ts = sampling_time;
00154
00155 esc_controller.initController(K, omega, alpha, sampling_time);
00156
00157 disable_axis[x] = 0;
00158 disable_axis[y] = 0;
00159
00160 ROS_INFO("Extremum seeking controller initialized.");
00161 }
00162
00163 private:
00164
00165 double Ts;
00166 esc::EscBounded esc_controller;
00167 auv_msgs::BodyVelocityReqPtr nu_past;
00168 int count;
00169 double esc_Ts;
00170 bool newRange;
00171 ros::Subscriber subRange;
00172 };
00173 }
00174 }
00175
00176 int main(int argc, char* argv[])
00177 {
00178 ros::init(argc,argv,"esc_classic_control");
00179
00180
00181
00182
00183
00184
00185
00186
00187
00188
00189
00190
00191 labust::control::HLControl<labust::control::ESCControlBounded_UV,
00192 labust::control::EnableServicePolicy,
00193 labust::control::NoWindup,
00194 auv_msgs::BodyVelocityReq,
00195 auv_msgs::NavSts,
00196 std_msgs::Float32> controller;
00197 ros::spin();
00198
00199 return 0;
00200 }
00201
00202
00203
00204
00205
00206
00207