key: cord-1028240-dsstt9tp authors: Viridiana Vazquez-Carmona, E.; Vasquez-Gomez, Juan Irving; Herrera-Lozada, Juan Carlos; Antonio-Cruz, Mayra title: Coverage Path Planning for Spraying Drones date: 2022-03-28 journal: Comput Ind Eng DOI: 10.1016/j.cie.2022.108125 sha: fddda7b936a0b3d62062f68efb6a2c46516ece50 doc_id: 1028240 cord_uid: dsstt9tp The pandemic by COVID-19 is causing a devastating effect on the health of the global population. Currently, there are several efforts to prevent the spread of the virus. Among those efforts, cleaning and disinfecting public areas have become important tasks and they should be automated in future smart cities. To contribute in this direction, this paper proposes a coverage path planning method for a spraying drone, an unmanned aerial vehicle that has mounted a sprayer/sprinkler system, that can disinfect areas. State-of-the-art planners consider a camera instead of a sprinkler, in consequence, the expected coverage will differ in running time because the liquid dispersion is different from a camera’s projection model. In addition, current planners assume that the vehicles can fly outside the target region; this assumption can not be satisfied in our problem, because disinfections are performed at low altitudes. Our method presents i) a new sprayer/sprinkler model that fits a more realistic coverage volume to the drop dispersion and ii) a planning method that efficiently restricts the flight to the region of interest avoiding potential collisions in bounded scenes. The algorithm has been tested in several simulation scenes, showing that it is effective and covers more areas with respect to two approaches in the literature. Note that the proposal is not limited to disinfection applications, but can be applied to other ones, such as painting or precision agriculture. The pandemic by COVID-19 is causing a devastating effect on global public health. Because of that, various efforts have been made to face it. Among those efforts, cleaning and disinfection of public areas have been important. Therefore, tools that facilitate the task are needed. For this purpose, in the automation field, some tools have been provided, example of that are the diagnostic systems using computer vision and artificial intelligence techniques, human support robots for the cleaning and maintenance of door handles, and robotic automation for distribution of food and essentials [1, 2, 3 ]. Another example is the disinfection task, which involves spreading a liquid that cleans surfaces. So far, in the majority of cases, disinfecting is done by human workers that put their health at risk. To carry out the disinfection task in an autonomous fashion, a positioning system or robot moves an active sprinkler in such a way all Regions of Interest (ROI) are covered [4] . Within positioning systems, Unmanned Aerial Vehicles (UAVs), also known as drones, can move in three dimensions while they have a relatively low cost. In consequence, relatively large areas such as buildings, courts or halls can be disinfected quickly. See Fig. 1 as an example of the disinfection of a basketball court. Autonomous disinfection requires the integration of several techniques into one single application that is executed before the flight and also during it. First, the sprinkler coverage needs to be modeled. Next, the ROI has to be specified by defining a polygon in geodetic coordinates. Then the unmanned aerial vehicle (UAV) is prepared for the mission. Next, the flight mission is planned. Finally, the UAV automatically has to take off and follow the planned path. Among these tasks, this paper focuses on the sprinkler modelling and mission planning, which are carried out before flying. To be explicit, the sprinkler modeling determines the area that is covered by the sprayer from a fixed position, and the mission planning receives as input the ROI, the sprinkler model and the vehicle's capabilities in order to determine a set of waypoints that will be loaded in the on-board controller. The core problem in the planning stage is the Coverage Path Planning (CPP); which is defined as determining a path for a vehicle so that the ROI is covered [5] . The CPP has been demonstrated to be NP-Hard [6] . However, by making some geometrical assumptions on the problem it is possible to obtain near optimal paths with linear complexity algorithms [7] . In addition, planning for disinfection requires adequate modeling of the sprinkler system, otherwise, disinfection is compromised. After reviewing the literature on CPP for UAVs and spraying UAVs (whose detailed analysis is presented in section 2), two fashions were found: i) The one focusing on solving the CPP problem for UAVs, and ii) the second one concerning the spraying task without considering the CPP problem. However, the first fashion is mainly dedicated to applications on surveillance, obstacle avoidance, inspection, mapping, and reconnaissance of areas. Only four papers were dedicated to the CPP problem addressing the spraying task [8, 9, 10, 11] . In general, for crop areas, they neither consider the model of the sprinkler nor the collisions that may occur in the surrounding area. Also, those papers do not model the footprint of the sprinkler and some are limited to a certain shape of the terrain to perform the spraying task. In order to contribute in this direction, particularly to provide a spraying system for the autonomous disinfection useful to face the pandemic by COVID-19, this paper integrates the aforementioned fashions, developing a CPP method that allows disinfecting convex regions with a UAV. In this paper, we propose a mission planning method for area disinfection with a MAV that has mounted a sprinkler. In particular, the sprinkler is modeled as a 3D stochastic paraboloid whose intersection with the ground creates a disinfection footprint. Based on this footprint, the ROI area is eroded avoiding collisions and finally, the rotating calipers path planner [7] is extended to provide a final tour that visits omitted regions. The method has three advantages with respect to current methods: i) it integrates a stochastic sprinkler model, ii) the planned paths do not go outside the target region, and iii) the computation time is shorter with respect to the compared methods. To the best of our knowledge, this is the first method that models the sprinkler as a stochastic parabolid. In addition, it can plan the paths in almost in real time because we propose linear complexity procedures to extend the previous geometrical approach of [7] . Finally, this is one of the first methods than can be used in urban areas while the related work is focus on open spaces. To validate the method, we have performed more than one hundred simulation experiments, testing our method with several ROI shapes and versus two related methods. The results show that the proposed method can plan successful paths despite the shape of the ROIs. In addition, the proposed method has the shortest computation time, making an on-board implementation feasible. The rest of the article is presented as follows. In section, 2 we present the related work. In section, 3 we present our novel method for path planning. Section 4 describes the experiments that were carried out including a software in the loop simulation due to mobility restrictions. Finally, section 5 presents our conclusion and future research directions. Literature dealing with CPP for UAVs is as follows. Meivel et al. [8] developed a system for spraying pesticides and fertilizers in open crop fields. The spraying UAV was controlled through manual flight plans. The UAV had a camera to capture remote sensing images, with the purpose of identifying green fields and the edges of the crop areas. The remote sensing images were analyzed by QGIS software to generate a map of the area. Also, Torres et al. [12] presented a method to solve the CPP problem to obtain a path that reduces battery consumption by decomposing non-convex polygons into convex areas. First of all, the UAV has a camera mounted. Then, it captures images from the ROI. Later, to perform the polygon coverage, the algorithm generates a back-and-forth movement or zigzag motion, the algorithm computes the distances between two straight movements using the overlap and the camera footprint. Finally, it returns a path that minimizes the number of UAV turns. Keller et al. [13] planned G 2 feasible paths for a UAV provided with a camera by concatenating G 2 curves in order to achieve persistent surveillance missions. An augmented A* algorithm was used to find a cycle sequence for the surveillance ROI This sequence was used in a B-spline curve generation algorithm to develop smooth paths that satisfy curvature constraints. For the same task, Xiao et al. [14] proposed a path planning algorithm based on the continuous updating of the virtual regional field and its local gradients. This virtual field incorporated a Boolean function which contains the information of the target regions and the obstacle information that forms a logical map. When a nonzero gradient at each point is in the regional field, the UAV finds the following target regions. Also, Stefas et al. [15] introduced an autonomous aerial system on a multi-rotor UAV navigating on an orchard for crop inspection. With a stereo camera yield data was collected from the ROI. For this, components for the UAV navigation, obstacle detection and avoidance based on vision, and CPP were developed. The autonomous aerial system used a global planner to enter, exit, and navigate to the next tree, also integrates a local planner to navigate on the tree rows. By their part, Freitas et al. [16] combined area coverage planning with path planning for biological pest control by releasing capsules with a UAV. The locations to release the capsules in the infected areas were calculated using the hexagon as base geometry. The capsule was placed only if its center was within the infected areas. Then, a capsule was placed in the center of mass of each remaining sub-polygon of the previous step, whereas the path planning was achieved with ant colony optimization, guided local search, and Lin-Kernighan algorithms. Furthemore, Gao et al. [9] proposed a method to solve CPP for precise spraying in peach orchards. For that, a binocular color depth sensor was used to acquire video images. Then, a color depth fusion segmentation method based on the leaf wall area of the color depth images was proposed. Additionally, image erosion was used to delineate the two largest leaf wall areas as an ROI. The path of the spraying UAV was planned by detecting the midpoint of the ROI spacing as the end of the spray path. Also, Dong et al. [17] proposed an artificially weighted spanning tree coverage algorithm for the trajectory planning of flying robots. The robots simultaneously built their spanning tree, which grew toward the center of inertia of the uncovered area while stayed away from the trees of its partners. To go forward the tree, each robot iteratively evaluates the discovered cells and then selects the one having a maximum weight. According with this weighting, the selected cell is added to the spanning tree covering an area. By their part, Vasquez et al. [7] proposed a rotating calipers path planner that computes the full path to cover a convex ROI from a 2D perspective for disaster management or precision agriculture. The drone carried a pinhole camera during the mission and took photos of the ROI. The algorithm iteratively adds waypoints by intersecting a line with the ROI's polygon. The algorithm requires parameters such as the polygon, an initial vertex, an adjacent vertex, an antipodal vertex, and the distance between flight lines. Furthermore, Skorobogatov et al. [18] presented an algorithm open-source to divide any convex and non-convex polygon area into multiple parts, including any number of no-fly zones. Later, trajectories for the UAV were assigned. For the task, the UAV took pictures that were joined to obtain a complete map after a flight. The algorithm had as input a polygon defining the ROI, the initial positions of the UAV, the mission parameters, and a convex divisor function based on Hert and Lumelsky algorithm. Moreover, Tang et al. [19] introduced a CPP method based on a Region Optimal Decomposition (ROD) using a multi-rotor UAV in a maritime port for concave polygons. They applied the ROD to a Google Earth image of a port and combining the resulting sub-regions through an improved depth-firstsearch algorithm. Then, a genetic algorithm determined the traversal order of all sub-regions and connect the coverage paths. Alternatively to genetic algorithms, Bat algorithms [20] can deal with the problem of optimizing the traversal order. By their part, Yao et al. [10] proposed a mission assignment scheme for the farmland spraying problem by using multi-quadcopters. To solve the problem a mathematical model for the mission assignment and a sequential quadratic programming method to obtain the optimal solution were used. Thus, quadcopters can spray pesticides covering the farmland, but spraying is prohibited over areas covered by different quadcopters. Phung et al. [21] formulated the inspection path planning problem as an extended Travelling Salesman Problem (TSP) for a UAV. They introduced a discrete particle swarm optimization (DPSO) algorithm using deterministic initialization, random mutation, and edge exchange to resolve the problem. The UAV has a CCD camera to detect potential defects or damages in the inspected area and, then, find the shortest path for the inspection of the planar surface. They used parallel computing for the velocity, position, and aptitude of the particles. The parallel program was implemented on a Jetson board mounted on the UAV using the MAVLink protocol. Also, Vasquez et al. [22] introduced a CPP method addressing disjoint areas based on the rural postman problem. The problem was resolved by optimizing the order of visits and computing the back-and-forth pattern. They converted the convex polygon into a reduced graph, and they treated the problem as the TSP, solving it by implementing a genetic algorithm. Finally, to compute the back-andforth pattern, they found the visiting order, sorted the polygons and the set of vertices through their planner proposed. Muliawan et al. [11] proposed a path planning approach for a UAV to carry out the spraying process in a plantation. A Modified Particle Swarm optimization (PSO) algorithm is used for the spraying task. The spraying process is carried out depending on the severity of disease of the plantation, which ranges from moderate to low. Recently, Gonzalez et al. [23] presented an approach to CPP for zigzag paths performed by a UAV in a three-dimensional environment. An optimization process based on the Differential Evolution (DE) algorithm is used in combination with the fast marching square scheduler. The UAV kept a fixed altitude to obtain images of a terrain, maintaining a homogeneous pixel size without overlapping. From the obtained images, a method to generate the zigzag path was used. Then, the DE algorithm optimizes zigzag path so that the steering angle of the UAV is optimal, ensuring a minimal distance cost. Campo et al. [24] proposed a data acquisition system using a low-cost Lightweight UAV (LUAV) with a camera to cover areas of interest and obtain a continuous map in crops. The LUAV optimized the coverage paths using a heuristic strategy, where a waypoint for the navigation of the LUAV agent was the center of the footprint of the camera. Zuo et al. [25] introduced a linear programming model to maximize coverage area and minimize coverage time for intelligence, surveillance, and reconnaissance missions with UAVs. In the first stage, a mission planner determined the search pattern, Point of Interest (POI), and the ROI for each UAV. In the second stage, the mission planner assigns some ROIs and flight paths for each UAV in the mission. Lastly, the aggregated mixed-integer linear programming for the path planning problem is solved by using the branch-and-bound algorithm in the CPLEX solver. Shang et al. [26] presented a co-optimal CPP approach to generate an aerial inspection path that optimized coverage of a 3D surface and quality of the captured images, and reduced the computational complexity of the solver. The approach found the feasible paths for complete visual coverage. Later, a collection of the sampled paths were introduced in a PSO, which integrated the quality and efficiency of a coverage path in an objective function. Then, the calculated path was transferred to a flight trajectory using the rapidly exploring random tree to avoid obstacles. Tamayo et al. [27] designed and implemented a software system to plan low-cost drone coverage for surveillance in agricultural or forested polygonal areas. The user specifies a start location and charging station (CS) locations. Then, the drone took a video of the area and creates a binary grid representation of the observed field. To minimize time to loading stations and field configurations, the branch-and-bound algorithm was implemented, which finds a minimal set of CSs that minimized distance and decomposed the field into Voronoi regions. After that, it computed a path using the modified TSP algorithm and constructs the paths. More recently, Biundini et al. [28] presented a framework for CPP for inspection with UAVs. They designed a metaheuristic algorithm based on point cloud data to inspect structures and coupling 3D reconstructions. First, the camera of the UAV captured a moving image of the surface or ROI. The data of the structure is imported in point cloud or mesh format. Then, the data removed outliers and reduced the points of the optimization algorithm to identify the surface shape. After that, a genetic algorithm created a waypoint mission. Lastly, the path was sent to the UAV to start the flight, avoiding the UAV to waste energy. Popescu et al. [29] designed a remote system to determine flooded areas through image processing with fixed-wing type UAVs. The system integrated terrestrial and aerial components. The first one is a coordinator at a distance of the UAV, which has a ground control station that communicated with more ground data terminals, via internet, through a network of nodes for data acquisition for agricultural fields which included a water pump connected to a fertilizer tank monitored with a sensor. When a certain threshold was reached the user was notified to fill the tank. In the work of Rao et al. [35] a semiautonomous agricultural spraying system for pesticides was developed. The spraying system was connected to a control board, which in turn was connected to an Arduino board, which generates pulses to activate a DC motor and thus spray the pesticide. By they part, Uddin et al. Table 1 . Lastly, other important contributions associated with flight controllers for UAVs and spraying methods are found in [44, 45, 46] and [47, 48, 49, 50] , respectively. In this section, we present our method for automatically disinfect a twodimensional area with an unmanned aerial vehicle that carries a sprinkler. The proposed method is composed of several parts, see Fig. 2 where we show how such parts interact. First, we compute a sprinkler model using a regression approach that fits data obtained from the drop distribution to a paraboloid shape. Then, the sprinkler model, the ROI shape and the vehicle's Then, the planner uses these parameters to obtain a path. Finally, the computed path is used by the UAV to complete the mission. Our contributions are remarked in gray. capabilities are used to plan a path. The path, given by a set of waypoints, is loaded into the on-board controller that guides the vehicle through the set of waypoints. Below, we first introduce the sprinkler modeling, and then we present the coverage path planning. There are several ways to model a sprinkler system depending on the application and system characteristics [51] . In this work, we assume that only one sprinkler is mounted on the UAV and that the vehicle's altitude is where h is the drone altitude, x and y are coordinates on the plane, and the parameters A and B define the amplitude of the paraboloid. Fig. 3 shows the proposed model. This model is closer to the reality w.r.t. previous models such as squares or cones. However, a deterministic model is still limited because in real sprinklers, the dispersion effect is much more complex given that many variables contribute to the drop's fall [51] . To insert such variability in our model, we consider the drop's fall as a stochastic process that affects the paraboloid shape, in consequence, we update equation (1) with a random noise. where σ is a random error from a normal distribution with zero mean, µ = 0, and standard deviation equal to σ. Fig. 4b shows an example of this noisy model. In many cases, the sprinkler is not characterized by the maker, however, a model fitting can be carried out so that the parameters A and B can be inferred using data from the drop's fall for a given sprinkler. In this method, we use the Levenberg-Marquardt Algorithm [52] for finding the paraboloid parameters (Â,B). Fig. 4c shows an example of a fitted model for a given set of observed drops. Next, let us assume that the terrain is horizontal, therefore, given the position of the vehicle, the spray footprint on the ground is determined by the intersection of the fitted paraboloid, equation (1) , and the floor plane. In general, such footprint is described by an ellipsoidal shape. However, we restrict the intersection between the paraboloid and the floor to a circle. Look at Fig. 3 . The circle is the biggest one that fits into the ellipsoidal intersection. This restriction has several vantages: i) the plan is conservative, meaning that in the worst case more area is disinfected, ii) the path planning is simplified and iii) the processing efficiency is improved. A more detailed plan considering irregular footprints is left for future work. In summary, the footprint forms a circle, where its limit is given by the circumference with equation: where r is the circle's radius and (a, b) is the center of the circumference. The proof of the intersection between the paraboloid and the plane is straightforward, so it is omitted. Then, from now on, the area that is sprayed inside the circle will be called as the drone's footprint. Once the vehicle is moving, the footprint evolves to a disinfected lane. Once the footprint has been stablished, the coverage path planning is defined as computing a vehicle's path in such a way that the ROI is completely covered by the footprint. The ROI is defined as a convex polygon, whose area is bigger than the footprint. Otherwise, the path is a single point. In addition, a constraint is that the vehicle must stay inside the ROI, e.g., for indoor scenes, the robot must avoid collision with doors and walls. To solve the problem, we propose a method based on back-and-forth paths. This strategy simplifies the problem to finding a path composed by straight movements, called flight lines, in a similar way than a boustrophedon covers a terrain [53] . The method is summarized in algorithm 1 and described next. The requirements are the polygon (M ), the footprint radius (r), the takeoff point (s) and the landing point (e). First, the method establishes the distance between flight lines, δ, as two times the foot print radius. By setting δ = 2r, we guarantee that there is no gaps between flight of lines. Unlike previous literature [12] , we do not require overlap between flight lines since we assume that a single exposition to the spray is enough for disinfecting the area. Second, the ROI's polygon is eroded by a circular kernel of diameter equal to r. shows the inclusion of the final tour to the path. In this section, we present several experiments for validating our method. First, we test the method with several polygon shapes, where each shape is defined by a fixed number of vertices but the size of the edges might vary. In that experiment, we compare our method versus two state-of-theart approaches. Second, we simulate the execution of the proposed method in a realistic scenario, this simulation was set as close as possible to a real disinfection. So far, validating our method with real world experiments has been impossible due to current travel and mobility restrictions imposed by COVID19. Our implementation was done using several programming frameworks. The planners were implemented in MatLab; they read the target polygon and ouput the path. A second implementation in C++ reads the path and communicates with the the Gazebo simulator to perform a software in the loop real time simulation. In this experiment, the proposed method is tested and compared versus two state-of-the-art methods. The goal is to show that the method can deal with the polygons despite their shape. The first of the compared methods is the proposed by Choset el at. [53] , where vertical back-and-forth paths are computed to cover the regions. The second compared method is the one proposed by Torres et al. [12] ; in that method, the flight lines are oriented perpendicularly to the minimum polygon width. For the comparison, we have performed a statistical analysis where several polygons of different shapes are tested with each method. In detail, we randomly create five polygons for each shape from a set of eight shapes. The set of shapes includes polygons from three vertices to ten vertices. In consequence, 120 tests were carried out in real-time simulations. Fig. 7 where we compare the paths for three random polygons. For the other two methods, the paths are outside the target polygon, so the vehicle can collide or it can get into restricted areas. The processing time for the proposed approach is 0.06 seconds in average, while the time for Torres's algorithm is 0.136 seconds and the time for the Choset's algorithm is 0.60 seconds on average. The reason why our method takes less time to compute the path is due to the rotating calipers path planner, which computes the path with linear complexity with respect to the number of vertices. This fact has already been proved in [7] . A natural consequence of our method is that the path length is increased given that it performs a final tour around the target polygon for covering the missed regions. In Table 2 , we can observe this increment in distance, which is small if it is compared versus the Choset's method. [12] and Choset et al. [53] . In all cases, the target polygons are draw with dashed lines and the path is drawn with solid lined. Figure best seen in color. The objective of this experiment is to validate that the method works in a more realistic simulation. See Fig. 8 . Due to the current situation, it was not possible to run the experiments in a real vehicle. However, the Gazebo simulator was configured with closest to reality parameters. In addition, we want to provide a qualitative display of the planned task. We draw a polygon on the edge of the area surrounding one of the Bi- centennial Park basketball courts located in Mexico City using the Mission Planner software. Later, the coordinates define the ROI. Next, the coordinates are converted from geodetic coordinates (latitude, longitude, and height) to NED coordinates (North, East, and Down). The erosion function in the algorithm is in charge of reducing the border of the area that will depend on the radius of the sensor, and once it has the area, it continues to the creation of the flight lines. However, it is required to visit all the areas so that as much as possible is covered. The algorithm adds the nodes of all the polygon vertices to cover areas without visiting. Then a conversion from NED coordinates to geodetic coordinates is performed again to add these coordinates to a waypoints file. The Gazebo simulator uses the waypoints file to carry out the path over the court. Subsequently, for this simulation, SITL was used in collaboration with the Gazebo 9 simulator to see the area in 3D. In this simulation, the Quadcopter 3DR Iris was used. The height set during the simulation was 10 meters. The speed of the drone is 2m/s. The starting point is set with the coordi- The proposed method has three advantages over the compared methods: i) avoiding potential collisions since the paths are inside the target areas, ii) providing more realistic modeling of the sprinkler and iii) shorter computation times. Avoiding potential collisions is one of the main features of the planner, since its application is oriented to low altitude missions. The processing time of the proposed approach is shorter because it is based on the rotating calipers algorithm to compute the inner path. With respect to traveling distance, our method computes a larger path since it performs a (a) Planned path. (b) Online excecution of the path. final tour around the polygon to cover missed areas. A method for planning two-dimensional area disinfection with an UAV has been presented. Our method improves previous approaches by includ- ing a more precise sprinkler modeling, restricts the vehicle flight inside the Region of Interest and requires shorter computation times. In consequence, it improves coverage and avoids potential collisions. Those characteristics make it suitable for being implemented in vehicles flying in urban scenarios. Through several experiments, we have validated our method; in those experiments, we observed that the vehicle covers the area of disinfection despite the area shape. Furthermore, the method has shown to be efficient enough for being implemented in onboard systems with low computational capacity. For future work, we plan to extend our method for non-convex polygons and to carry out real-world experiments. Novel coronavirus (covid-19) diagnosis using computer vision and artificial intelligence techniques: a review A Human Support Robot for the Cleaning and Maintenance of Door Handles Using a Deep-Learning Framework Drive Through Robotics: Robotic Automation for Last Mile Distribution of Food and Essentials During Pandemics Rahman, Unmanned aerial vehicle for cleaning and firefighting purposes A survey on coverage path planning for robotics Approximation algorithms for lawn mowing and milling Coverage path planning for 2d convex regions Quadcopter uav based fertilizer and pesticide spraying system A spraying path planning algorithm based on colour-depth fusion segmentation in peach orchards A pesticide spraying mission assignment performed by multi-quadcopters and its simulation platform establishment Uav path planning for autonomous spraying task at salak plantation based on the severity of plant disease Coverage path planning with unmanned aerial vehicles for 3D terrain reconstruction Coordinated Path Planning for Fixed-Wing UAS Conducting Persistent Surveillance Missions Low-Complexity Path Planning Algorithm for Unmanned Aerial Vehicles in Complicated Scenarios Vision-based monitoring of orchards with UAVs Use of UAVs for an efficient capsule distribution and smart path planning for biological pest control An Artificially Weighted Spanning Tree Coverage Algorithm for Decentralized Flying Robots Flight planning in multi-unmanned aerial vehicle systems: Nonconvex polygon area decomposition and trajectory assignment A Coverage Path Planning Approach Based on Region Optimal Decomposition A modified bat algorithm with torus walk for solving global optimisation problems Enhanced discrete particle swarm optimization path planning for UAV visionbased surface inspection 2018 International Conference on Unmanned Aircraft Systems (ICUAS) Coverage Mission for UAVs Using Differential Evolution and Fast Marching Square Methods, IEEE Aerospace and Electronic Systems Magazine Optimization of coverage mission for lightweight unmanned aerial vehicles applied in crop data acquisition MILP Formulation for Aircraft Path Planning in Persistent Surveillance A co-optimal coverage path planning method for aerial scanning of complex structures Foerster, Cost-Minimizing System Design for Surveillance of Large, Inaccessible Agricultural Areas Using Drones of Limited Range A Framework for Coverage Path Planning Optimization Based on Point Cloud for Structural Inspection Unmanned Aerial Vehicle Systems for Remote Estimation of Flooded Areas Based on Complex Image Processing Distributed Energy-Efficient Multi-UAV Navigation for Long-Term Communication Coverage by Deep Reinforcement Learning A Bioinspired Neural Network-Based Approach for Cooperative Coverage Planning of UAVs Development of a spray system for an unmanned aerial vehicle platform Droplet deposition and control effect of insecticides sprayed with an unmanned aerial vehicle against plant hoppers Design & development of agricultural fertilizer spraying drone with remote controller and autonomous control with low weight aluminium alloy frame structure Design and modelling of anaffordable uav based pesticide sprayer in agriculture applications Unmanned aerial vehicle for cleaning the high rise buildings A virtual reality interface for an autonomous spray painting uav Effects of spray parameters of drone on the droplet deposition in sugarcane canopy Servicio de agricultura de precisión con drones: Sky solutions méxico Agras mg-1s drtk drone para agricultura Dji t16 dron para fumigar de 16l Uav vtol and nbsp;dronehexaag Gaia 160ag-agricultural spraying drone arf combo Development of a pwm precision spraying controller for unmanned aerial vehicles Develop an unmanned aerial vehicle based automatic aerial spraying system Freyr drone: Pesticide/fertilizers spraying drone -an agricultural approach Harvest aids efficacy applied by unmanned aerial vehicles on cotton crop Drones support in precision agriculture for fighting against parasites Effect of aerial spray adjuvant applying on the efficiency of small unmanned aerial vehicle for wheat aphids control Field evaluation of an unmanned aerial vehicle (uav) sprayer: effect of spray volume on deposition and the control of pests and disease in wheat Mathematical modelling and simulation of irrigation sprinklers A method for the solution of certain non-linear problems in least squares Coverage path planning: The boustrophedon cellular decomposition conceptualization, software, writing. J. Irving Vasquez-Gomez: conceptualization, methodology, writing. Juan Carlos Herrera-Lozada: resources. Mayra Antonio-Cruz: validation, writing, review and editing