|
|
|
|
@ -14,74 +14,196 @@ void FollowerClass::follower(){
|
|
|
|
|
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
void FollowerClass::plane(global_location target_location,global_location leader_location,global_location follower_location){
|
|
|
|
|
void FollowerClass::plane(global_location target, global_location leader, global_location follower){
|
|
|
|
|
|
|
|
|
|
//caculate drone is locate on R/L plane
|
|
|
|
|
float slope,c,y;
|
|
|
|
|
slope = (target_location.lat-leader_location.lat)/(target_location.lon-leader_location.lon);
|
|
|
|
|
c = target_location.lat - slope*target_location.lon;
|
|
|
|
|
y = slope * follower_location.lon + c;
|
|
|
|
|
|
|
|
|
|
if(follower_location.lat >= y){
|
|
|
|
|
drone1.plane = 1; //right plane
|
|
|
|
|
y = slope * follower.lon + c;
|
|
|
|
|
|
|
|
|
|
if(follower.lat > y){
|
|
|
|
|
switch (follower.ID){
|
|
|
|
|
case 1:
|
|
|
|
|
drone1.init_location.lat = follower.lat;
|
|
|
|
|
drone1.init_location.lon = follower.lon;
|
|
|
|
|
drone1.plane = -1; //right plane
|
|
|
|
|
break;
|
|
|
|
|
case 2:
|
|
|
|
|
drone2.init_location.lat = follower.lat;
|
|
|
|
|
drone2.init_location.lon = follower.lon;
|
|
|
|
|
drone2.plane = -1;
|
|
|
|
|
break;
|
|
|
|
|
case 3:
|
|
|
|
|
drone3.init_location.lat = follower.lat;
|
|
|
|
|
drone3.init_location.lon = follower.lon;
|
|
|
|
|
drone3.plane = -1;
|
|
|
|
|
break;
|
|
|
|
|
}
|
|
|
|
|
}else if(follower_location.lat < y){
|
|
|
|
|
drone1.plane = 0; //left plane
|
|
|
|
|
switch (follower.ID){
|
|
|
|
|
case 1:
|
|
|
|
|
drone1.init_location.lat = follower.lat;
|
|
|
|
|
drone1.init_location.lon = follower.lon;
|
|
|
|
|
drone1.ID = follower.ID;
|
|
|
|
|
drone1.plane = 1; //left plane
|
|
|
|
|
break;
|
|
|
|
|
case 2:
|
|
|
|
|
drone2.init_location.lat = follower.lat;
|
|
|
|
|
drone2.init_location.lon = follower.lon;
|
|
|
|
|
drone2.plane = 1;
|
|
|
|
|
break;
|
|
|
|
|
case 3:
|
|
|
|
|
drone3.init_location.lat = follower.lat;
|
|
|
|
|
drone3.init_location.lon = follower.lon;
|
|
|
|
|
drone3.plane = 1;
|
|
|
|
|
break;
|
|
|
|
|
}
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
choose_leader();
|
|
|
|
|
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
void FollowerClass::choose_leader(){
|
|
|
|
|
void FollowerClass::find_ref_drone(global_location data[], size_t index, int leaderID){
|
|
|
|
|
|
|
|
|
|
for(int i=1 ; i<index ; i++){ //check leader drone
|
|
|
|
|
if(leaderID = data[i].ID){
|
|
|
|
|
leader_drone = data[i];
|
|
|
|
|
switch(leaderID){
|
|
|
|
|
case 1:
|
|
|
|
|
drone1.init_location.lat = data[i].lat;
|
|
|
|
|
drone1.init_location.lon = data[i].lon;
|
|
|
|
|
drone1.ID = data[i].ID;
|
|
|
|
|
drone1.plane = 0; //center
|
|
|
|
|
break;
|
|
|
|
|
case 2:
|
|
|
|
|
drone2.init_location.lat = data[i].lat;
|
|
|
|
|
drone2.init_location.lon = data[i].lon;
|
|
|
|
|
drone2.ID = data[i].ID;
|
|
|
|
|
drone2.plane = 0;
|
|
|
|
|
break;
|
|
|
|
|
case 3:
|
|
|
|
|
drone3.init_location.lat = data[i].lat;
|
|
|
|
|
drone3.init_location.lon = data[i].lon;
|
|
|
|
|
drone3.ID = data[i].ID;
|
|
|
|
|
drone3.plane = 0;
|
|
|
|
|
break;
|
|
|
|
|
|
|
|
|
|
}
|
|
|
|
|
}
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
for(int i=1 ; i<index ; i++){
|
|
|
|
|
if(data[i].ID != leader_drone.ID){ //caculate the plane of each drone
|
|
|
|
|
plane(data[0],leader_drone,data[i]);
|
|
|
|
|
}
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
int j=0,k=0;
|
|
|
|
|
if(drone1.ID == data[1].ID){ //seperate self and other
|
|
|
|
|
self = drone1;
|
|
|
|
|
}else{
|
|
|
|
|
memberDrone[j] = drone1;
|
|
|
|
|
j+=1;
|
|
|
|
|
}
|
|
|
|
|
if(drone2.ID == data[1].ID){
|
|
|
|
|
self = drone2;
|
|
|
|
|
}else{
|
|
|
|
|
memberDrone[j] = drone2;
|
|
|
|
|
j+=1;
|
|
|
|
|
}
|
|
|
|
|
if(drone3.ID == data[1].ID){
|
|
|
|
|
self = drone1;
|
|
|
|
|
}else{
|
|
|
|
|
memberDrone[j] = drone3;
|
|
|
|
|
j+=1;
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
for(int i=0;i<index-1;i++){
|
|
|
|
|
if(memberDrone[i].plane == self.ID){
|
|
|
|
|
samePlane[k] = memberDrone[i];
|
|
|
|
|
k++;
|
|
|
|
|
}
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
int s_index = sizeof(samePlane)/sizeof(samePlane[0]);
|
|
|
|
|
float d[s_index];
|
|
|
|
|
int check_ID;
|
|
|
|
|
|
|
|
|
|
for(int i=0 ; i<s_index ; i++){
|
|
|
|
|
|
|
|
|
|
d[i] = sqrt( pow((self.init_location.lat - samePlane[i].init_location.lat ),2) + pow((self.init_location.lat - samePlane[i].init_location.lat),2) );
|
|
|
|
|
|
|
|
|
|
// std::cout << i<<"," <<d[data[i].ID] <<std::endl;
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
std::vector<float> _d(d,d+s_index-1);
|
|
|
|
|
|
|
|
|
|
check_ID = std::distance(_d.begin(),std::min_element(_d.begin(),_d.end())); //get minimum value's index
|
|
|
|
|
|
|
|
|
|
// std::cout <<"Drone " << " is leader " << std::endl;
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
void FollowerClass::get_location(){
|
|
|
|
|
|
|
|
|
|
// lon[0]
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
void FollowerClass::calculate_position(float k,float theta){
|
|
|
|
|
|
|
|
|
|
theta = theta*3.14/180;
|
|
|
|
|
float phi = request_object.get_leader_heading()/100;
|
|
|
|
|
phi = phi*3.14/180;
|
|
|
|
|
leader_location=request_object.get_leader_GPS();
|
|
|
|
|
follower_location=GPS_object.gps_position();
|
|
|
|
|
|
|
|
|
|
double Pf[]={},Pl[]={leader_location.lon,leader_location.lat};
|
|
|
|
|
float transfer[2][2]={
|
|
|
|
|
cos(phi),-sin(phi),
|
|
|
|
|
sin(phi),cos(phi)
|
|
|
|
|
};
|
|
|
|
|
float Q[2]={k*sin(theta),k*cos(theta)};
|
|
|
|
|
float T[2]={1,-1};
|
|
|
|
|
|
|
|
|
|
Pf[0]=(transfer[0][0]*Q[0]+transfer[0][1]*Q[1])*T[0]+Pl[0]/100;
|
|
|
|
|
Pf[1]=(transfer[1][0]*Q[0]+transfer[1][1]*Q[1])*T[1]+Pl[1]/100;
|
|
|
|
|
|
|
|
|
|
float error_x = Pf[0] - (follower_location.lon*1e+5);
|
|
|
|
|
float error_y = Pf[1] - (follower_location.lat*1e+5);
|
|
|
|
|
|
|
|
|
|
if (error_x < 0.3 & error_x > -0.3){
|
|
|
|
|
error_x = 0;
|
|
|
|
|
}
|
|
|
|
|
if (error_y < 0.3 & error_y > -0.3){
|
|
|
|
|
error_y = 0;
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
// ROS_INFO("%f,%f",leader_location.lon/100 ,leader_location.lat/100);
|
|
|
|
|
ROS_INFO("%f,%f",follower_location.lon*1e+5 ,follower_location.lat*1e+5);
|
|
|
|
|
ROS_INFO("%f,%f",Pf[0],Pf[1]);
|
|
|
|
|
ROS_INFO("%f,%f",error_x,error_y);
|
|
|
|
|
ROS_INFO("************************************");
|
|
|
|
|
|
|
|
|
|
command_object.fix_velocity(error_x,error_y,0,0,0.1);
|
|
|
|
|
// sleep(0.5);
|
|
|
|
|
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
void FollowerClass::get_location(){
|
|
|
|
|
|
|
|
|
|
// lon[0]
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
// void FollowerClass::calculate_position(float k,float theta){
|
|
|
|
|
|
|
|
|
|
// theta = theta*3.14/180;
|
|
|
|
|
// float phi = request_object.get_leader_heading()/100;
|
|
|
|
|
// phi = phi*3.14/180;
|
|
|
|
|
// leader_location=request_object.get_leader_GPS();
|
|
|
|
|
// follower_location=GPS_object.gps_position();
|
|
|
|
|
|
|
|
|
|
// double Pf[]={},Pl[]={leader_location.lon,leader_location.lat};
|
|
|
|
|
// float transfer[2][2]={
|
|
|
|
|
// cos(phi),-sin(phi),
|
|
|
|
|
// sin(phi),cos(phi)
|
|
|
|
|
// };
|
|
|
|
|
// float Q[2]={k*sin(theta),k*cos(theta)};
|
|
|
|
|
// float T[2]={1,-1};
|
|
|
|
|
|
|
|
|
|
// Pf[0]=(transfer[0][0]*Q[0]+transfer[0][1]*Q[1])*T[0]+Pl[0]/100;
|
|
|
|
|
// Pf[1]=(transfer[1][0]*Q[0]+transfer[1][1]*Q[1])*T[1]+Pl[1]/100;
|
|
|
|
|
|
|
|
|
|
// float error_x = Pf[0] - (follower_location.lon*1e+5);
|
|
|
|
|
// float error_y = Pf[1] - (follower_location.lat*1e+5);
|
|
|
|
|
|
|
|
|
|
// if (error_x < 0.3 & error_x > -0.3){
|
|
|
|
|
// error_x = 0;
|
|
|
|
|
// }
|
|
|
|
|
// if (error_y < 0.3 & error_y > -0.3){
|
|
|
|
|
// error_y = 0;
|
|
|
|
|
// }
|
|
|
|
|
|
|
|
|
|
// // ROS_INFO("%f,%f",leader_location.lon/100 ,leader_location.lat/100);
|
|
|
|
|
// ROS_INFO("%f,%f",follower_location.lon*1e+5 ,follower_location.lat*1e+5);
|
|
|
|
|
// ROS_INFO("%f,%f",Pf[0],Pf[1]);
|
|
|
|
|
// ROS_INFO("%f,%f",error_x,error_y);
|
|
|
|
|
// ROS_INFO("************************************");
|
|
|
|
|
|
|
|
|
|
// command_object.fix_velocity(error_x,error_y,0,0,0.1);
|
|
|
|
|
// // sleep(0.5);
|
|
|
|
|
|
|
|
|
|
// }
|
|
|
|
|
|