app3.cpp
Go to the documentation of this file.
00001 
00023 #include "app3/app3.h"
00024 
00025 #define PI 3.14159265358979323846
00026 #define EPSILON 0.1
00027 #define A 5
00028 #define B 5
00029 const double C = abs(A-B) / sqrt(4*A*B);
00030 #define H 0.2
00031 #define D 10
00032 #define R 12
00033 #define C1 0.3
00034 #define C2 0.3
00035 
00036 double pm1=1,pm2=3,pm3=1;
00037 
00038 using namespace std;
00039 
00040 class NeighborHandle
00041 {
00042     public:
00043     double _px,_py,_vx,_vy;
00044     pair<double,double> _position,_velocity;
00045     int _r_id; 
00046     double mypm_g;
00047     NeighborHandle(int r_id, float x, float y, float vx, float vy)
00048     {
00049         
00050         _px=x;
00051         _py=y;
00052         _vx=vx;
00053         _vy=vy;
00054         _position=pair<double,double>(x,y);
00055         _velocity=pair<double,double>(vx,vy);
00056         _r_id = r_id;
00057         mypm_g=1;
00058     }
00059 };
00060 
00061 static list<NeighborHandle*> neighbor_list;
00062 pair<double,double> my_position=pair<double,double>(0,0);
00063 pair<double,double> my_velocity=pair<double,double>(0,0);
00064 
00065 pair<double,double> get_vector(pair<double,double> start,pair<double,double> end)
00066 {
00067     pair<double,double> re=pair<double,double>(0,0);
00068     re.first=end.first-start.first;
00069     re.second=end.second-start.second;
00070     return re;
00071 }
00072 
00073 double segma_norm(pair<double,double> v)
00074 {
00075     double re = EPSILON*(v.first*v.first+v.second*v.second);
00076     re = sqrt(1+re)-1;
00077     re /= EPSILON;
00078     return re;
00079 }
00080 
00081 double R_alpha = segma_norm(pair<double,double>(R,0));
00082 double D_alpha = segma_norm(pair<double,double>(D,0));
00083 
00084 pair<double,double> segma_epsilon(pair<double,double> v)
00085 {
00086     pair<double,double> re = pair<double,double>(0,0);
00087     double scale = 1+EPSILON*(v.first*v.first+v.second*v.second);
00088     scale = sqrt(scale);
00089     re.first = v.first / scale;
00090     re.second = v.second / scale;
00091     return re;
00092 }
00093 
00094 double segma_1(double z)
00095 {
00096     return z / sqrt(1+z*z);
00097 }
00098 
00099 double phi(double z)
00100 {
00101     return 0.5*((A+B)*segma_1(z+C)+A-B);
00102 }
00103 
00104 double rho(double z)
00105 {
00106     if(z<H)
00107         return 1;
00108     if(z>1)
00109         return 0;
00110     return 0.5*(1+cos(PI*(z-H)/(1-H)));
00111 }
00112 
00113 double phi_alpha(double z)
00114 {
00115     return rho(z/R_alpha)*phi(z-D_alpha);
00116 }
00117 
00118 pair<double,double> f_g()
00119 {
00120     pair<double,double> re = pair<double,double>(0,0);
00121     for(list<NeighborHandle*>::iterator i=neighbor_list.begin();i!=neighbor_list.end();i++)
00122     {
00123         pair<double,double> q_ij = get_vector(my_position,(*i)->_position);
00124         pair<double,double> n_ij = segma_epsilon(q_ij);
00125         re.first += phi_alpha(segma_norm(q_ij))*n_ij.first*(*i)->mypm_g;
00126         re.second += phi_alpha(segma_norm(q_ij))*n_ij.second*(*i)->mypm_g;
00127     }
00128     return re;
00129 }
00130 
00131 double a_ij(pair<double,double> j_p)
00132 {
00133     return rho(segma_norm(get_vector(my_position,j_p)) / R_alpha);
00134 }
00135 
00136 pair<double,double> f_d()
00137 {
00138     pair<double,double> re = pair<double,double>(0,0);
00139     for(list<NeighborHandle*>::iterator i=neighbor_list.begin();i!=neighbor_list.end();i++)
00140     {
00141         pair<double,double> p_ij = get_vector(my_velocity,(*i)->_velocity);
00142         re.first += a_ij((*i)->_position) * p_ij.first;
00143         re.second += a_ij((*i)->_position) * p_ij.second;
00144     }
00145     return re;
00146 }
00147 
00148 double interval = 0.01;
00149 pair<double,double> f_r()
00150 {
00151     pair<double,double> re = pair<double,double>(0,0);
00152     static pair<double,double> q_r = pair<double,double>(0,0);
00153     pair<double,double> p_r = pair<double,double>(0.5,0.5);
00154     q_r.first += p_r.first * interval;
00155     q_r.second += p_r.second * interval;
00156     re.first = -C1*get_vector(q_r,my_position).first - C2*get_vector(p_r,my_velocity).first;
00157     re.second = -C1*get_vector(q_r,my_position).second - C2*get_vector(p_r,my_velocity).second;
00158     return re;
00159 }
00160 
00161 // Register the application
00162 PLUGINLIB_EXPORT_CLASS(app3::App3, micros_swarm::Application)
00163 
00164 namespace app3{
00165 
00166     App3::App3() {}
00167     
00168     App3::~App3() {}
00169 
00170     void App3::stop(){}
00171     
00172     void App3::init()
00173     {
00174         //set parameters
00175         hz = 10;
00176         interval = 1.0/hz;
00177     }
00178     
00179     void App3::publish_cmd(const ros::TimerEvent&)
00180     {
00181         geometry_msgs:: Twist msg;
00182         micros_swarm::Neighbors<micros_swarm::NeighborBase> n(true);
00183 
00184         typename std::map<int, micros_swarm::NeighborBase>::iterator it;
00185         for(it = n.data().begin(); it != n.data().end(); it++) {
00186             NeighborHandle* nh = new NeighborHandle(it->first, it->second.x, it->second.y, it->second.vx, it->second.vy);
00187             neighbor_list.push_back(nh);
00188         }
00189 
00190         micros_swarm::Base nl = get_base();
00191 
00192         my_position=pair<double,double>(nl.x, nl.y);
00193         my_velocity=pair<double,double>(nl.vx, nl.vy);
00194       
00195         msg.linear.x += (f_g().first*pm1+f_d().first*pm2+f_r().first*pm3)/hz;
00196         msg.linear.y += (f_g().second*pm1+f_d().second*pm2+f_r().second*pm3)/hz;
00197         //cout<<f_g().second<<' '<<f_d().second<<' '<<msg.linear.y<<endl;
00198       
00199         if (msg.linear.x > 1) {
00200             msg.linear.x = 1;
00201         }
00202         if (msg.linear.x < -1) {
00203             msg.linear.x = -1;
00204         }
00205         if (msg.linear.y > 1) {
00206             msg.linear.y = 1;
00207         }
00208         if (msg.linear.y <- 1) {
00209             msg.linear.y = -1;
00210         }
00211         pub.publish(msg);
00212         neighbor_list.clear();  
00213     }
00214     
00215     void App3::baseCallback(const nav_msgs::Odometry& lmsg)
00216     {
00217         float x = lmsg.pose.pose.position.x;
00218         float y = lmsg.pose.pose.position.y;
00219     
00220         float vx = lmsg.twist.twist.linear.x;
00221         float vy = lmsg.twist.twist.linear.y;
00222     
00223         micros_swarm::Base l(x, y, 0, vx, vy, 0, 1);
00224         set_base(l);
00225     }
00226     
00227     void App3::start()
00228     {
00229         init();
00230 
00231         ros::NodeHandle nh;
00232         set_dis(12);
00233         pub = nh.advertise<geometry_msgs::Twist>("cmd_vel", 1000);
00234         sub = nh.subscribe("base_pose_ground_truth", 1000, &App3::baseCallback, this, ros::TransportHints().udp());
00235         ros::Duration(5).sleep();  //this is necessary, in order that the runtime platform kernel of the robot has enough time to publish it's base information.
00236         
00237         timer = nh.createTimer(ros::Duration(interval), &App3::publish_cmd, this);
00238     }
00239 };
00240 


app3
Author(s):
autogenerated on Thu Jun 6 2019 18:52:24