path_planning.cpp
Go to the documentation of this file.
00001 /*
00002  *  This file is part of ucl_drone 2016.
00003  *  For more information, refer
00004  *  to the corresponding header file.
00005  *
00006  * This file receives information from Strategy and the Pose_estimation and publishes to the
00007  * Controller.
00008  * It tells the controller where the drone must go as function of the strategy and the position of
00009  * the drone.
00010  *
00011  *  \authors Julien Gérardy & Félicien Schiltz
00012  *  \date 2016
00013  *
00014  */
00015 
00016 #include "ucl_drone/path_planning.h"
00017 
00018 PathPlanning::PathPlanning()
00019 {
00020   // drone prefix from the launch file.
00021   std::string drone_prefix;
00022   ros::param::get("~drone_prefix", drone_prefix);
00023 
00024   // List of subscribers and publishers. This node subscribes to pose_estimation to get the
00025   // real-time
00026   // position of the drone. It also subsribes to Stragegy in order to know in what the drone must do
00027   // and so where it has to go.
00028   // This node publishes in the node path_planning that communicates with the controller and to the
00029   // node mapcell that is just used to export data from tests.
00030 
00031   // Subscribers
00032   pose_channel = nh.resolveName("pose_estimation");
00033   pose_sub = nh.subscribe(pose_channel, 10, &PathPlanning::poseCb, this);
00034 
00035   strategy_channel = nh.resolveName("strategy");
00036   strategy_sub = nh.subscribe(strategy_channel, 10, &PathPlanning::strategyCb, this);
00037 
00038   // Publishers
00039   poseref_channel = nh.resolveName("path_planning");
00040   poseref_pub = nh.advertise< ucl_drone::PoseRef >(poseref_channel, 1);
00041 
00042   // Just for some tests
00043   mapcell_channel = nh.resolveName("mapcell");
00044   mapcell_pub = nh.advertise< ucl_drone::cellUpdate >(mapcell_channel, 500);
00045 
00046   // instruction_publishing = false;
00047 }
00048 
00049 // Destructor
00050 
00051 PathPlanning::~PathPlanning()
00052 {
00053 }
00054 
00055 // Function to reset the desired pose sent to the controller
00056 void PathPlanning::reset()
00057 {
00058   next_x = 0;
00059   next_y = 0;
00060   next_z = 1;
00061   next_rotZ = 0;
00062   i = 0;
00063   landing = false;
00064   takeoff = false;
00065   gridInitialized = false;
00066 
00067   // XMax and YMax are the half of the distance between the horizontal and vertical border lines of
00068   // the vision of the drone. Those values come from bottom camera data and 0.8 is used as a
00069   // security factor in the case of the drone is not well oriented.
00070 
00071   XMax = next_z * 0.435 * 0.8 * 0.5;
00072   YMax = next_z * 0.326 * 0.8 * 0.5;
00073 }
00074 
00075 // This function publish the position where the drone has to get. It is used as pose_ref in the
00076 // controller node.
00077 void PathPlanning::publish_poseref()
00078 {
00079   // instantiate the poseref message
00080   ucl_drone::PoseRef poseref_msg;
00081 
00082   poseref_msg.x = next_x;
00083   poseref_msg.y = next_y;
00084   poseref_msg.z = next_z;
00085   poseref_msg.rotZ = next_rotZ;
00086   poseref_msg.landAndStop = landing;
00087   poseref_msg.takeoffAndStart = takeoff;
00088 
00089   poseref_pub.publish(poseref_msg);
00090 }
00091 
00092 // This function is called when this node receives a message from the topic "pose_estimation". So it
00093 // takes this message and put it in a variable where it will be used in the other functions.
00094 
00095 void PathPlanning::poseCb(const ucl_drone::Pose3D::ConstPtr posePtr)
00096 {
00097   lastPoseReceived = *posePtr;
00098 }
00099 
00100 // This function is called when this node receives a message from the topic "strategy". So it
00101 // takes this message and put it in a variable where it will be used in the other functions.
00102 
00103 void PathPlanning::strategyCb(const ucl_drone::StrategyMsg::ConstPtr strategyPtr)
00104 {
00105   lastStrategyReceived = *strategyPtr;
00106 }
00107 
00108 // First approach to explore a map. The drones makes a kind of labyrinth
00109 
00110 bool PathPlanning::xy_desired()
00111 {
00112   // The drone is considered as "arrived on poseref if it in a radius of 0.35m"
00113   if (sqrt((lastPoseReceived.x - next_x) * (lastPoseReceived.x - next_x) +
00114            (lastPoseReceived.y - next_y) * (lastPoseReceived.y - next_y)) < 0.35)
00115   {
00116     printf("i: %d\n", i);
00117     if (i % 2 == 0)
00118     {
00119       next_x += 1;
00120     }
00121     else if (i % 4 == 1)
00122     {
00123       next_y += 1;
00124     }
00125     else  //(i%4==3)
00126     {
00127       next_y -= 1;
00128     }
00129     i++;
00130     return true;
00131   }
00132   else
00133   {
00134     return false;
00135   }
00136 }
00137 
00138 // In our final approach to expore the map, the pathplanning creates a grid. This grid is made of
00139 // 0.10*0.10 m² cells that can be in 3 different states :
00140 // 0 means unseen/unexplored
00141 // 1 means seen/explored
00142 // 2 means border cell explored (there is cells behind but we haven't seen them yet)
00143 // 3 means wall cell detected
00144 
00145 void PathPlanning::InitializeGrid()
00146 {
00147   // Set all the cells to "unexplored"
00148   for (i = 0; i < SIDE * 10; i++)
00149   {
00150     for (j = 0; j < SIDE * 10; j++)
00151     {
00152       myGrid[i][j] = 0;
00153     }
00154   }
00155   gridInitialized = true;
00156 }
00157 
00158 // This function creates a virtual wall. It returns true if the cell (i,j) contains a wall. This
00159 // function has to be replaced by a true wall identification function via a camera and image process
00160 // (for example). This function has been made in order where it can easily be replaced by something
00161 // real and with more performances.
00162 
00163 bool PathPlanning::ThereIsAWallCell(int i, int j)  // modified
00164 {
00165   yfromcell2 = -((j / 10.0) - SIDE / 2.0);
00166   xfromcell2 = SIDE - (i / 10.0);
00167 
00168   // ROS_INFO("i is :  %d    , j is : %d \n", i, j);
00169   // ROS_INFO("xfromcell2 is : %lf    , yfromcell2 is : %lf \n", xfromcell2, yfromcell2);
00170 
00171   if (yfromcell2 >= (SIDE / 2.0 - 0.2) || yfromcell2 <= -(SIDE - 0.4) / 2.0)
00172   {
00173     return true;
00174   }
00175   else if (xfromcell2 >= SIDE - 0.2 || xfromcell2 <= 0.2)
00176   {
00177     return true;
00178   }
00179   else
00180   {
00181     return false;
00182   }
00183 }
00184 
00185 // This function trasnforms the XMax and Ymax into the panel of cells that are seen by the drone in
00186 // function of its position.
00187 // !! abscisse = I and ordoonee = J
00188 void PathPlanning::AbsOrdMinMax(double x, double y, int* iMin, int* iMax, int* jMin, int* jMax)
00189 {
00190   printf("I'm calculating AbsOrdMinMax\n");
00191   *jMin = fmax(0, (int)(10 * SIDE / 2.0 - (y + YMax) * 10));
00192   *jMax = fmin((int)(10 * SIDE / 2.0 - (y - YMax) * 10), SIDE * 10);
00193   *iMin = fmax(0, (int)(10 * SIDE - (x + XMax) * 10));
00194   *iMax = fmin((int)(10 * SIDE - (x - XMax) * 10), SIDE * 10);
00195 }
00196 
00197 // This function transforms i and j coordinates to x and y position in the real playground.
00198 void PathPlanning::CellToXY(int i, int j, double* xfromcell, double* yfromcell)
00199 {
00200   *yfromcell = (double)(SIDE / 2.0 - j / 10.0);
00201   *xfromcell = (double)SIDE - (i / 10.0);
00202 }
00203 
00204 // This function is the main one of the grid. It checks all the cells that the drone is seeing and
00205 // modify their value in regard with the previous grid and the "ThereIsAWallCell" function.
00206 void PathPlanning::UpdateMap(double x, double y)
00207 {
00208   ROS_INFO("I'm in the updatemap function");
00209   AbsOrdMinMax(x, y, &myAbsMin, &myAbsMax, &myOrdMin, &myOrdMax);
00210   ROS_INFO("I'm in the updatemap function after absOrdMinMax function");
00211   printf("myOrdMin: %d     myOrdMax: %d      myAbsMin: %d    myAbsMax: %d   \n", myOrdMin, myOrdMax,
00212          myAbsMin, myAbsMax);
00213   ucl_drone::cellUpdate cellUpdateMsg;
00214   for (i = myAbsMin; i < myAbsMax; i++)
00215   {
00216     for (j = myOrdMin; j < myOrdMax; j++)
00217     {
00218       // ROS_INFO("I'm in the updatemap loop for (i,j) %d, %d \n", i, j);
00219 
00220       if (myGrid[i][j] == 0 || myGrid[i][j] == 2)
00221       {
00222         if (!ThereIsAWallCell(i, j))
00223         {
00224           if (i == myAbsMin || i == myAbsMax - 1 || j == myOrdMin || j == myOrdMax - 1)
00225           {
00226             if (myGrid[i][j] == 2)
00227             {
00228               printf("I put a border cell\n");
00229             }
00230             else
00231             {
00232               printf("I put a NEW border cell\n");
00233               cellUpdateMsg.i = i;
00234               cellUpdateMsg.j = j;
00235               cellUpdateMsg.type = 2;
00236               mapcell_pub.publish(cellUpdateMsg);
00237             }
00238             myGrid[i][j] = 2;
00239           }
00240           else
00241           {
00242             myGrid[i][j] = 1;
00243             printf("I put an explored cell\n");
00244             cellUpdateMsg.i = i;
00245             cellUpdateMsg.j = j;
00246             cellUpdateMsg.type = 1;
00247             mapcell_pub.publish(cellUpdateMsg);
00248           }
00249         }
00250         else
00251         {
00252           myGrid[i][j] = 3;
00253           printf("I put a wall cell\n");
00254           cellUpdateMsg.i = i;
00255           cellUpdateMsg.j = j;
00256           cellUpdateMsg.type = 3;
00257           mapcell_pub.publish(cellUpdateMsg);
00258         }
00259       }
00260     }
00261   }
00262 }
00263 
00264 // This function returns the distance between two cells.
00265 double PathPlanning::distance(int i, int j, int k, int l)
00266 {
00267   return sqrt((i - k) * (i - k) + (j - l) * (j - l));
00268 }
00269 
00270 // This function replaced the labyrtinth one. It takes as argument the position of the drone and
00271 // gives back the best cell where the drone must go. In order to do that, it compares all the border
00272 // cells of the map and tell the drone to go to the nearrest one.
00273 void PathPlanning::advanced_xy_desired(double x, double y, double* k, double* l)
00274 {
00275   int absc = (int)(SIDE - x) * 10;
00276   int ord = (int)(SIDE / 2.0 - y) * 10;
00277   bestDist = 1000000.0;
00278   closestJ = SIDE * 10 / 2.0;
00279   closestI = SIDE * 10;
00280   for (i = 0; i < SIDE * 10; i++)
00281   {
00282     for (j = 0; j < SIDE * 10; j++)
00283     {
00284       if (myGrid[i][j] == 2 && distance(absc, ord, i, j) < bestDist)
00285       {
00286         bestDist = distance(absc, ord, i, j);
00287         closestJ = j;
00288         closestI = i;
00289       }
00290     }
00291   }
00292   if (bestDist == 1000000.0)
00293   {
00294     ROS_INFO("The map was explored completely, there are no more border cells!");
00295   }
00296   // printf("closestI should be  50 and is: %d \n", closestI);
00297   CellToXY(closestI, closestJ, k, l);
00298 }
00299 
00300 // This function give to the object variable the computed next reference position.
00301 void PathPlanning::SetRef(double x_ref, double y_ref, double z_ref, double rotZ_ref)
00302 {
00303   this->next_x = x_ref;
00304   this->next_y = y_ref;
00305   this->next_z = z_ref;
00306   this->next_rotZ = rotZ_ref;
00307 }
00308 
00309 // Main function, will publish pose_ref with regard to the selected strategy comming from the
00310 // Strategy node.
00311 int main(int argc, char** argv)
00312 {
00313   ROS_INFO_STREAM("poseref_sending started!");
00314   ros::init(argc, argv, "path_planning");
00315   PathPlanning myPath;
00316   ros::Rate r(20);  // Refresh every 1/20 second.
00317   printf("Pathplanning launched");
00318   ROS_DEBUG("path planning initialized");
00319 
00320   myPath.reset();
00321   myPath.publish_poseref();
00322   ros::spinOnce();
00323   r.sleep();
00324   ROS_INFO_STREAM("poseref initialized and launched");
00325   while (ros::ok())
00326   {
00327     TIC(path);
00328     if (myPath.lastStrategyReceived.type == 1.0)  // This corresponds to the takeoff strategy.
00329     {
00330       myPath.takeoff = true;
00331       myPath.publish_poseref();
00332     }
00333 
00334     // Strategy == 7.0 and == 8.0 are never true. Those numbers are just used to change the response
00335     // we want from the pathplanning between 3 different functions. (test - labyrinth - grid). We
00336     // just have to put 2.0 to the one we want and other numbers to the others.
00337 
00338     // This function calls the labyrinth pathplanning.
00339     else if (myPath.lastStrategyReceived.type == 7.0)
00340     {
00341       if (myPath.xy_desired() == true)
00342       {
00343         myPath.takeoff = true;
00344         ros::Duration(5).sleep();
00345         myPath.publish_poseref();
00346       }
00347     }
00348 
00349     // Strategy = GOTO, the drone goes directly to the position writed in the message from the
00350     // strategy.
00351     else if (myPath.lastStrategyReceived.type == 3.0)
00352     {
00353       myPath.takeoff = true;
00354       myPath.SetRef(myPath.lastStrategyReceived.x, myPath.lastStrategyReceived.y + 0.5,
00355                     myPath.next_z,
00356                     myPath.next_rotZ);  // Pas correct, ne tient pas compte de la
00357                                         // position du drone maitre
00358       myPath.publish_poseref();
00359     }
00360 
00361     // Strategy = Land, the drone lands.
00362     else if (myPath.lastStrategyReceived.type == 4.0)
00363     {
00364       myPath.takeoff = false;
00365       myPath.landing = true;
00366       myPath.publish_poseref();
00367     }
00368 
00369     // Strategy = Follow, the drone goes to the coordinates writed in the message from the strategy.
00370     // Those ones come from the target_detected channel in the strategy node.
00371     else if (myPath.lastStrategyReceived.type == 5.0)
00372     {
00373       myPath.takeoff = true;
00374       myPath.SetRef(myPath.lastStrategyReceived.x, myPath.lastStrategyReceived.y, myPath.next_z,
00375                     myPath.next_rotZ);
00376       myPath.publish_poseref();
00377     }
00378 
00379     // Strategy = BackToBase, the drone rises up to 2m in order to avoid the other drone coming to
00380     // replace him. Then it goes back to the base and land when it is in a radius of 0.15m from
00381     // where it took off.
00382     else if (myPath.lastStrategyReceived.type == 6.0)
00383     {
00384       myPath.next_z = 2;
00385       if (sqrt((myPath.lastPoseReceived.x) * (myPath.lastPoseReceived.x) +
00386                (myPath.lastPoseReceived.y) * (myPath.lastPoseReceived.y)) < 0.15)
00387       {
00388         myPath.takeoff = false;
00389         myPath.landing = true;
00390       }
00391       else if (!myPath.landing)
00392       {
00393         myPath.takeoff = true;
00394         myPath.SetRef(0, 0, myPath.next_z, myPath.next_rotZ);
00395       }
00396       myPath.publish_poseref();
00397     }
00398 
00399     // Strategy = Seek (explore), the drone initializes the grid. Then this is the
00400     // advanced_xy_desired function that tells the drone where to go.
00401     else if (myPath.lastStrategyReceived.type == 2.0)
00402     {
00403       if (!myPath.gridInitialized)
00404       {
00405         ROS_INFO("I am initializing the grid");
00406 
00407         myPath.InitializeGrid();
00408       }
00409 
00410       myPath.takeoff = true;
00411       myPath.UpdateMap(myPath.lastPoseReceived.x, myPath.lastPoseReceived.y);
00412       ROS_INFO("I have updated the map");
00413 
00414       myPath.advanced_xy_desired(myPath.lastPoseReceived.x, myPath.lastPoseReceived.y,
00415                                  &myPath.poseRefX, &myPath.poseRefY);
00416       myPath.SetRef(myPath.poseRefX, myPath.poseRefY, myPath.next_z, myPath.next_rotZ);
00417       ROS_INFO("poseref is : (%lf, %lf)", myPath.poseRefX, myPath.poseRefY);
00418       ros::Duration(1).sleep();
00419       myPath.publish_poseref();
00420     }
00421 
00422     // Test of command for the report.
00423     else if (myPath.lastStrategyReceived.type == 8.0)
00424     {
00425       myPath.takeoff = true;
00426       myPath.SetRef(0.0, 0.0, 1.0, 0.0);
00427       myPath.publish_poseref();
00428       ros::Duration(15).sleep();
00429       myPath.SetRef(2.0, 0.0, 1.0, 0.0);
00430       myPath.publish_poseref();
00431       ros::Duration(35).sleep();
00432       myPath.SetRef(0.0, 0.0, 1.0, 0.0);
00433       myPath.publish_poseref();
00434       ros::Duration(35).sleep();
00435       myPath.SetRef(-2.0, 0.0, 1.0, 0.0);
00436       myPath.publish_poseref();
00437       ros::Duration(35).sleep();
00438     }
00439 
00440     TOC(path, "path planning");
00441     ros::spinOnce();
00442     r.sleep();
00443   }
00444 
00445   return 0;
00446 }
00447 
00448 // Function that gives a yaw angle in order to always face to the direction to go. We don't use it
00449 // at this moment.
00450 
00451 /*void PathPlanning::yaw_desired()
00452 {
00453   double delta_x=next_x-lastPoseReceived.x;
00454   double delta_y=next_y-lastPoseReceived.y;
00455   if(sqrt(delta_x*delta_x+delta_y*delta_y)<1.5)
00456   {
00457   next_yaw=old_next_yaw;
00458   }
00459   else
00460   {
00461   double theta;
00462   if(delta_x!=0)
00463   {
00464   theta=atan(delta_y/delta_x);
00465   }
00466   else
00467   {
00468   theta=3.14159;
00469   }
00470   if(delta_y<0 && delta_x<0)
00471   {
00472   theta+=3.14159;
00473       if(theta>3.14159)
00474       {
00475           theta=theta-2*3.14159;
00476       }
00477   }
00478   else if(delta_y>0 && delta_x<0)
00479   {
00480   theta=abs(theta);
00481   }
00482   old_next_yaw=next_yaw;
00483   next_yaw=theta;
00484   }
00485 
00486 }
00487 */


ucl_drone
Author(s): dronesinma
autogenerated on Sat Jun 8 2019 20:51:53