|
|
|
|
@ -45,15 +45,42 @@ void FollowerClass::follower(global_location** member_data, size_t index, int re
|
|
|
|
|
|
|
|
|
|
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->lat-leader->lat)/(target->lon-leader->lon);
|
|
|
|
|
//calculate drone is locate on R/L plane
|
|
|
|
|
|
|
|
|
|
float phi = leader->heading/100 ;
|
|
|
|
|
// phi = phi*3.14/180;
|
|
|
|
|
|
|
|
|
|
if (phi > 355 && phi < 5){
|
|
|
|
|
phi = 0;
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
// float ref_y = leader->lat + 5000;
|
|
|
|
|
// float ref_x = leader->lon + 1;
|
|
|
|
|
// ref_point.lon = (cos(-phi)*leader->lon + sin(-phi)*ref_y);
|
|
|
|
|
// ref_point.lat = (-sin(-phi)*leader->lon + cos(-phi)*ref_y);
|
|
|
|
|
|
|
|
|
|
ref_point.lon = 5000*sin(phi*3.14/180) + leader->lon + 1;
|
|
|
|
|
ref_point.lat = 5000*cos(phi*3.14/180) + leader->lat;
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
slope = (ref_point.lat-leader->lat)/(ref_point.lon-leader->lon);
|
|
|
|
|
c = leader->lat - slope*leader->lon;
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
// if((target->lat != pre_target.lat) || (target->lon != pre_target.lon)){
|
|
|
|
|
// slope = (target->lat-leader->lat)/(target->lon-leader->lon);
|
|
|
|
|
// c = leader->lat - slope*leader->lon;
|
|
|
|
|
// }
|
|
|
|
|
|
|
|
|
|
y = slope * follower->lon + c;
|
|
|
|
|
|
|
|
|
|
pre_target.lat = target->lat;
|
|
|
|
|
pre_target.lon = target->lon;
|
|
|
|
|
// std::cout<< follower.ID << ","<< follower.lat <<","<< y <<std::endl;
|
|
|
|
|
std::cout<< "slope: " << slope <<std::endl;
|
|
|
|
|
|
|
|
|
|
if(follower->lat <= y){
|
|
|
|
|
// std::cout<< follower.lat <<","<< y <<std::endl;
|
|
|
|
|
if((follower->lat <= y && phi < 180) || (follower->lat > y && phi >= 180)){
|
|
|
|
|
// std::cout <<"drone :"<<follower->ID <<", plane: 1" <<std::endl;
|
|
|
|
|
switch (follower->ID){
|
|
|
|
|
case 1:
|
|
|
|
|
drone1.init_location.lat = follower->lat;
|
|
|
|
|
@ -86,8 +113,8 @@ void FollowerClass::plane(global_location* target, global_location* leader, glob
|
|
|
|
|
drone5.plane = 1;
|
|
|
|
|
break;
|
|
|
|
|
}
|
|
|
|
|
}else if(follower->lat > y){
|
|
|
|
|
// std::cout<< follower.lat <<","<< y <<std::endl;
|
|
|
|
|
}else if((follower->lat > y && phi < 180) || (follower->lat <= y && phi >= 180)){
|
|
|
|
|
// std::cout <<"drone :"<<follower->ID <<", plane: -1" <<std::endl;
|
|
|
|
|
switch (follower->ID){
|
|
|
|
|
case 1:
|
|
|
|
|
drone1.init_location.lat = follower->lat;
|
|
|
|
|
@ -127,21 +154,55 @@ void FollowerClass::plane(global_location* target, global_location* leader, glob
|
|
|
|
|
|
|
|
|
|
int FollowerClass::direct(global_location* target, global_location* leader, DroneStatus self, DroneStatus member){
|
|
|
|
|
|
|
|
|
|
float m,n,k,cosTheta;
|
|
|
|
|
//Calculate whether the vector (SM) of self and member N is the same as the flight direction (LT)
|
|
|
|
|
|
|
|
|
|
float phi = leader->heading/100 ;
|
|
|
|
|
phi = phi*3.14/180;
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
// float ref_y = leader->lat + 5000;
|
|
|
|
|
// float ref_x = leader->lon + 1;
|
|
|
|
|
ref_point.lon = 5000*sin(phi) + leader->lon;
|
|
|
|
|
ref_point.lat = 5000*cos(phi) + leader->lat;
|
|
|
|
|
|
|
|
|
|
// vector_LT.lon = target->lon - leader->lon; //vector_LT (leader->target)
|
|
|
|
|
// vector_LT.lat = target->lat - leader->lat;
|
|
|
|
|
|
|
|
|
|
if(flag == 0){
|
|
|
|
|
vector_LT.lon = target->lon - leader->lon; //vector_LT (leader->target)
|
|
|
|
|
vector_LT.lat = target->lat - leader->lat;
|
|
|
|
|
flag = 1;
|
|
|
|
|
}
|
|
|
|
|
vector_SM.lon = member.init_location.lon - self.init_location.lon; //vector_SM (self->member)
|
|
|
|
|
vector_SM.lat = member.init_location.lat - self.init_location.lat;
|
|
|
|
|
k = (vector_LT.lon*vector_SM.lon)+(vector_LT.lat*vector_SM.lat); //k = vector_LT dot vector_SM
|
|
|
|
|
m = sqrt(pow(vector_LT.lon,2)+pow(vector_LT.lat,2)); //m = |vector_LT|
|
|
|
|
|
|
|
|
|
|
vector_LR.lon = ref_point.lon - leader->lon; //vector_LR (leader->Ref)
|
|
|
|
|
vector_LR.lat = ref_point.lat - leader->lat;
|
|
|
|
|
|
|
|
|
|
k = (vector_LR.lon*vector_SM.lon)+(vector_LR.lat*vector_SM.lat); //k = vector_LT dot vector_SM
|
|
|
|
|
m = sqrt(pow(vector_LR.lon,2)+pow(vector_LR.lat,2)); //m = |vector_LT|
|
|
|
|
|
n = sqrt(pow(vector_SM.lon,2)+pow(vector_SM.lat,2)); //n = |vector_SM|
|
|
|
|
|
|
|
|
|
|
// pre_m = sqrt(pow(pre_LT.lon,2)+pow(pre_LT.lat,2));
|
|
|
|
|
// pre_k = (pre_LT.lon*vector_SM.lon)+(pre_LT.lat*vector_SM.lat);
|
|
|
|
|
// if(pre_m != 0 && ((target->lat == pre_tar.lat) && (target->lon == pre_tar.lon))){
|
|
|
|
|
|
|
|
|
|
// u = (vector_LT.lon*pre_LT.lon)+(vector_LT.lat*pre_LT.lat);
|
|
|
|
|
// LTcos = u / (m*pre_m);
|
|
|
|
|
// if (LTcos < 0){
|
|
|
|
|
// m = pre_m;
|
|
|
|
|
// k = pre_k;
|
|
|
|
|
// std::cout <<"memberID: "<<member.ID << " fix" << std::endl;
|
|
|
|
|
// }
|
|
|
|
|
// std::cout <<"dir_test "<< std::endl;
|
|
|
|
|
|
|
|
|
|
// }else{
|
|
|
|
|
// pre_LT = vector_LT;
|
|
|
|
|
// pre_tar.lat = target->lat;
|
|
|
|
|
// pre_tar.lon = target->lon;
|
|
|
|
|
|
|
|
|
|
// }
|
|
|
|
|
|
|
|
|
|
cosTheta = k / (m*n);
|
|
|
|
|
// std::cout <<"drone: "<<self.ID<<"memberID: "<<member.ID << " ,cosTheta:"<< cosTheta << std::endl;
|
|
|
|
|
|
|
|
|
|
if(cosTheta > 0){
|
|
|
|
|
// std::cout <<"drone "<< self.ID <<"cosTheta: "<< cosTheta << std::endl;
|
|
|
|
|
if(cosTheta >= 0){
|
|
|
|
|
return 1;
|
|
|
|
|
}else{
|
|
|
|
|
return 10000;
|
|
|
|
|
@ -239,7 +300,7 @@ int FollowerClass::find_ref_drone(global_location** data, size_t index, int lead
|
|
|
|
|
if(memberDrone[i].plane == self.plane || memberDrone[i].plane == 0){ //load same plane member
|
|
|
|
|
samePlane[s_index] = memberDrone[i];
|
|
|
|
|
// std::cout << samePlane[s_index].init_location.lat <<std::endl;
|
|
|
|
|
// std::cout << memberDrone[i].ID <<std::endl;
|
|
|
|
|
// std::cout <<"drone"<<self.ID<<", memberdrone"<< memberDrone[i].ID<<", plane: "<< memberDrone[i].plane <<std::endl;
|
|
|
|
|
s_index++;
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
@ -256,7 +317,7 @@ int FollowerClass::find_ref_drone(global_location** data, size_t index, int lead
|
|
|
|
|
d[i] = dir * sqrt( pow((self.init_location.lat - samePlane[i].init_location.lat ),2) + pow((self.init_location.lon - samePlane[i].init_location.lon),2) );
|
|
|
|
|
|
|
|
|
|
// std::cout << i<<"," <<d[i] <<std::endl;
|
|
|
|
|
// std::cout << samePlane[i].ID <<std::endl;
|
|
|
|
|
// std::cout <<"drone" <<samePlane[i].ID<<" ,d = "<<d[i] <<std::endl;
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
std::vector<float> _d(d,d+s_index);
|
|
|
|
|
@ -264,8 +325,8 @@ int FollowerClass::find_ref_drone(global_location** data, size_t index, int lead
|
|
|
|
|
check_index = std::distance(_d.begin(),std::min_element(_d.begin(),_d.end())); //get minimum value's index
|
|
|
|
|
ref_ID = samePlane[check_index].ID;
|
|
|
|
|
|
|
|
|
|
std::cout <<"drone "<< self.ID <<",plane: "<< self.plane <<",refID: " << ref_ID << std::endl;
|
|
|
|
|
|
|
|
|
|
std::cout <<"drone "<< self.ID <<",plane: "<< self.plane <<",refID: " << ref_ID << ",mem_index: "<< s_index << std::endl;
|
|
|
|
|
std::cout <<"\n"<< std::endl;
|
|
|
|
|
return ref_ID;
|
|
|
|
|
|
|
|
|
|
}
|
|
|
|
|
@ -281,8 +342,14 @@ void FollowerClass::calculate_position(float k,float theta,int plane){
|
|
|
|
|
float heading = GPS_object.get_heading();
|
|
|
|
|
|
|
|
|
|
float phi = deg_phi*3.14/180; //degree-->radian
|
|
|
|
|
theta = plane*theta*3.14/180;
|
|
|
|
|
|
|
|
|
|
// if(deg_phi >= 180 && deg_phi < 350){
|
|
|
|
|
// plane = plane*-1;
|
|
|
|
|
// }else if((deg_phi >= 350 || deg_phi < 5) && pre_plane != 0){
|
|
|
|
|
// plane = pre_plane;
|
|
|
|
|
// }
|
|
|
|
|
theta = plane*theta*3.14/180;
|
|
|
|
|
pre_plane = plane;
|
|
|
|
|
double Pf[]={},Pl[]={refpos.lon ,refpos.lat}; //transfer maxtrix
|
|
|
|
|
float transfer[2][2]={
|
|
|
|
|
cos(phi),-sin(phi),
|
|
|
|
|
@ -306,7 +373,7 @@ void FollowerClass::calculate_position(float k,float theta,int plane){
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
float error_degree = deg_phi - heading;
|
|
|
|
|
float error_yaw = 0.2; //CCW
|
|
|
|
|
float error_yaw = 0.4; //CCW
|
|
|
|
|
|
|
|
|
|
if (error_degree >= 360){
|
|
|
|
|
error_degree -= 360;
|
|
|
|
|
@ -329,17 +396,17 @@ void FollowerClass::calculate_position(float k,float theta,int plane){
|
|
|
|
|
error_yaw = 0;
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
if (error_lon < -1){
|
|
|
|
|
error_lon = -1;
|
|
|
|
|
if (error_lon < -2){
|
|
|
|
|
error_lon = -2;
|
|
|
|
|
}
|
|
|
|
|
if (error_lon > 1){
|
|
|
|
|
error_lon = 1;
|
|
|
|
|
if (error_lon > 2){
|
|
|
|
|
error_lon = 2;
|
|
|
|
|
}
|
|
|
|
|
if (error_lat < -1){
|
|
|
|
|
error_lat = -1;
|
|
|
|
|
if (error_lat < -2){
|
|
|
|
|
error_lat = -2;
|
|
|
|
|
}
|
|
|
|
|
if (error_lat > 1){
|
|
|
|
|
error_lat = 1;
|
|
|
|
|
if (error_lat > 2){
|
|
|
|
|
error_lat = 2;
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
// ROS_INFO("%d,%f,%f",refpos.ID,refpos.lon ,refpos.lat );
|
|
|
|
|
|