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 #include <labust/control/SOIdentification.hpp>
00035 #include <labust/vehicles/vehiclesfwd.hpp>
00036 #include <labust/xml/GyrosReader.hpp>
00037 #include <labust/xml/GyrosWriter.hpp>
00038 #include <labust/tools/TimingTools.hpp>
00039 #include <labust/control/PIDController.hpp>
00040 
00041 #include <std_msgs/String.h>
00042 #include <ros/ros.h>
00043 
00044 #include <map>
00045 
00046 double yaw(0);
00047 double lastTime(labust::tools::unix_time());
00048 
00052 struct TuningParameters
00053 {
00057         double alpha,beta,betaa;
00061         double w;
00065         double max;
00066 };
00067 
00068 template <class PID>
00069 void tuneController(const TuningParameters& param, PID* pid)
00070 {
00071   double a3 = 1/(param.w*param.w*param.w), a2 = 3/(param.w*param.w), a1 = 3/(param.w);
00072 
00073   double K_Ipsi = param.alpha/a3;
00074   double K_Ppsi = param.alpha*a1/a3;
00075   double K_Dpsi = (param.alpha*a2/a3 - param.beta);
00076 
00077   
00078 
00079 
00080 
00081   
00082   pid->setGains(K_Ppsi,K_Ipsi,K_Dpsi,K_Dpsi/10);
00083 
00084   std::cout<<"Param:"<<param.alpha<<","<<param.beta<<","<<param.w<<std::endl;
00085   std::cout<<"K_Ppsi:"<<K_Ppsi<<",K_Ipsi:"<<K_Ipsi<<",K_Dpsi:"<<K_Dpsi<<std::endl;
00086 
00087   labust::math::Limit<double> limit(-param.max,param.max);
00088   pid->setLimits(limit);
00089 
00090   
00091 }
00092 
00093 void onState(const std_msgs::String::ConstPtr& msg)
00094 {
00095         labust::xml::GyrosReader reader(msg->data);
00096         labust::vehicles::stateMap state;
00097         reader.dictionary(state);
00098 
00099         yaw = state[labust::vehicles::state::yaw];
00100         lastTime = reader.GetTimeStamp();
00101 
00102         std::cout<<"Received."<<std::endl;
00103 }
00104 
00105 void sendTau(double torque,
00106                 const ros::Publisher& tau,  double lat = 0)
00107 {
00108   
00109   std::map<int,double> tauM;
00110   for (int i=labust::vehicles::tau::X; i<=labust::vehicles::tau::N; ++i)
00111   {
00112         tauM[i] = 0;
00113   }
00114 
00115   tauM[labust::vehicles::tau::N] = torque;
00116   tauM[labust::vehicles::tau::Y] = lat;
00117   tauM[labust::vehicles::tau::Z] = 0;
00118 
00119   labust::xml::GyrosWriter writer(tauM.begin(),tauM.end());
00120   writer.SetTimeStamp(true);
00121   std_msgs::String str;
00122   str.data = writer.GyrosXML();
00123   tau.publish(str);
00124 }
00125 
00126 int main(int argc, char* argv[])
00127 try
00128 {
00129         ros::init(argc, argv, "vehicleNode");
00130 
00131         ros::NodeHandle n;
00132 
00133 
00134         ros::Publisher tau = n.advertise<std_msgs::String>("tau", 10);
00135         ros::Subscriber state = n.subscribe("state",10,&onState);
00136 
00137   ros::Rate loop_rate(10);
00138   labust::control::SOIdentification ident;
00139 
00140  ident.setRelay(50,15*M_PI/180);
00141   ident.reset();
00142 
00143         
00144  labust::control::IPD ipd;
00145  
00146 
00147   double yaw_ref = 0;
00148  double ditter = 0*2.5;
00149   double lat = 0*80;
00150 
00151   
00152   int i=0;
00153 
00154   while (ros::ok())
00155   {
00156         ++i;
00157         if (!ident.isFinished())
00158         {
00159                 sendTau(ident.step(yaw_ref-yaw,0.1),tau);
00160                 
00161 
00162                 std::cout<<yaw<<std::endl;
00163         }
00164         else
00165         {
00166                 labust::control::SOIdentification::ParameterContainer param;
00167                 ident.parameters(¶m);
00168 
00169                 std::cout<<"Alpha:"<<param[ident.alpha];
00170                 std::cout<<", beta:"<<param[ident.kx];
00171                 std::cout<<", betaa:"<<param[ident.kxx];
00172                 std::cout<<", delta:"<<param[ident.delta]<<std::endl;
00173 
00174                 TuningParameters tparam;
00175 
00176                 tparam.w = 0.4;
00177                 tparam.alpha = param[ident.alpha];
00178                 tparam.beta = param[ident.kx];
00179                 tparam.betaa = param[ident.kxx];
00180                 tparam.max = 80;
00181 
00182                 tuneController(tparam,&ipd);
00183 
00184           
00185                 
00186                 
00187                 if ((i%100) == 0) lat = -lat;
00188           sendTau(ipd.step(yaw_ref, yaw) + ditter,tau, lat);
00189         }
00190 
00191     ros::spinOnce();
00192     
00193     loop_rate.sleep();
00194 
00195   }
00196 
00197   
00198   sendTau(0,tau);
00199 
00200         return 0;
00201 }
00202 catch (std::exception& e)
00203 {
00204         std::cerr<<e.what()<<std::endl;
00205 }
00206 
00207 
00208