Home A hybrid air-sea cooperative approach combined with a swarm trajectory planning method
Article Open Access

A hybrid air-sea cooperative approach combined with a swarm trajectory planning method

  • Salima Bella EMAIL logo , Assia Belbachir and Ghalem Belalem
Published/Copyright: April 29, 2020
Become an author with De Gruyter Brill

Abstract

This work addresses the issue of ocean monitoring and clean-up of polluted zones, as well as the notion of trajectory planning and fault tolerance for semi-autonomous unmanned vehicles. A hybrid approach for unmanned aerial vehicles (UAVs) is introduced to monitor the ocean region and cooperate with swarm of unmanned surface vehicles (USVs) to clean dirty zones. The paper proposes two solutions that apply to trajectory planning from the base of life to the dirty zone for swarm USVs. The first solution is performed by a modified Genetic Algorithm (GA), and the second uses a modified Ant Algorithm (AA). The proposed solutions were both implemented in the simulation with different scenarios for the dirty zone. This approach detects and reduces the pollution level in ocean zones while taking into account the problem of fault tolerance related to unmanned cleaning vehicles.

1 Introduction

Swarming is a collective behavior observed in animals of similar size, such as insects that gather and move in groups. In the context of robotics, swarm robotics is an approach for coordinating multi-robot systems [1, 2]. Most of the research carried out in cooperation with dynamic unmanned vehicles such as air, surface, ground unmanned, etc., has focused on formation control, which refers to the task of controlling these unmanned vehicles to follow a predefined trajectory while maintaining the desired formation pattern [3].

Path planning refers to the search for an optimal or sub-optimal path from the starting position to the goal in the environment. Trajectory planning is based on two key technologies: environmental modeling and planning algorithms. A reasonable model of the environment can help to reduce the amount of search and space occupancy over time [4], the grid representation, the geometry of space law, the topological method and electronic chart are reasonable models [5]. Grid method characteristics are simple, easy to implement and can be applied to different algorithms. Trajectory planning algorithms commonly include two methods: traditional planning and intelligent planning methods. Traditional methods include: artificial potential field method [6], A* method [7], D* method [8] and so on. Intelligent planning methods include: genetic algorithm [9], colony algorithm [5], neural network [10], particle swarm algorithm [2], etc. In addition, there is a mixed planning method based on the combination between traditional and intelligent planning.

According to [9], heuristic algorithms that implement searches in the solution space can be classified as instance-based or model-based algorithms. The instance-based algorithms generate new candidate solutions using the current solution or a population of solutions, such as genetic algorithms. GA are iterative stochastic optimization algorithms. They provide solutions to problems that do not have computational solutions in reasonable time analytic or algorithmic time. Model-based search algorithms generate candidate solutions using a parameterized probabilistic model, updated according to previous solutions. It allows the search to focus on regions containing high quality solutions such as Ant Colony Optimization (ACO).ACOis a meta-heuristic modeling based on the ant’s drilling behavior. Ant System (AS) was the first ACO algorithm applied to the travelling salesman problem (TSP) [11].

This work aims to present a hybrid hierarchical approach for a better management and easier control between the different unmanned vehicles. Moreover, this architecture allows fault tolerance and scalability compared to the self-organized approach that does not allow or hardly allows scalability with increased complexity for efficient management of its entities. Centralized management has a central node with deterministic decision-making capability and easy to implement coordination. This central node has a global view of the unmanned monitoring and cleaning swarm vehicles activities. Distributed management begins when the monitoring vehicle is assigned to a region. It has the ability to coordinate its cleaning swarms. These swarms plan their movement based on the proposed solutions to get to the dirty zones from their storage bases. These solutions propose a calculation method that quickly provides a workable solution to the planning problem. As this cleaning vehicle is a mechanical, electronic and computer system which may at some point fail at the hardware / software level, a solution is proposed to allow the replacement of failed vehicles by the competent cleaning vehicle during the realization of the cleaning mission.

This paper presents a hierarchical hybrid cooperative approach for heterogeneous unmanned vehicles. The approach includes two solutions to the trajectory planning problem for the unmanned surface vehicle (USV) swarm. The first one is based on the modified Genetic Algorithm, whereas the second relies on the modified Ant Algorithm. The proposed approach allows the cooperation of an unmanned aerial vehicle (UAV) to monitor an ocean region with an unmanned surface vehicles (USV) swarm to clean dirty oceanic zones. The UAV is assumed to be equipped with on-board sensors that allow it to locate dirty zones. The UAV discretizes its environment map and updates it with the collected information related to dirty zones. The UAV sends its environment map to its general coordinator (represented by a laptop and guided by a human operator). After an analysis of this collected data, the general coordinator allocates the explored map (way-points) to the USV swarm to clean each dirty zones. This swarm navigates to the assigned dirty zone and cleans it based on the proposed solutions. In addition, the proposed approach is complemented by a failure managing method of a USV during the execution of its cleaning task.

The remainder of this paper is organised as follows: Section 2 presents several related works; Section 3 describes the proposed approach for the different unmanned vehicles with the proposed solutions, and models them by logical formalization; in Section 4 the proposed approach is compared to the related works; Section 5 illustrates an example to simulate the operation of the proposed approach; finally, Section 6 concludes this paper and provides some future research directions.

2 Related works

Many heuristic and meta-heuristic algorithms have been applied to the path planning problem of unmanned vehicles, such as GA, ACO or PSO (more approaches can be found in [6]). In addition, several methods allow for coordination and control of multiple unmanned vehicles in a swarm or formation in trajectory planning [12] and to execute various applications such as cleaning, surveillance, rescue, detection and localization. For example, the CADDY cooperative orientation system which was proposed to monitor the behavior of human divers during the execution of missions at sea [13]. CADDY functionalities rely on the coordination of two robotic platforms, an Autonomous Surface Vehicle (ASV) and Autonomous Underwater Vehicles (AUV), and a guide. The cooperative path-following method is based on the virtual target approach. This method is developed in two stages (defined in [14, 15]). First, it relies on the consolidated single-vehicle virtual-target based path-following technique (using a Lyapunov function). Then, it extends the concept to a multi-vehicle system based on speed regulation, depending on the relative distance between the virtual targets (further details in [16]).

Thus, in [3], the authors introduced an improved swarm-based path-following guidance system for an autonomous multi-vehicle marine system. In the seminal idea, a team of USVs is required to join a formation using a potential-based swarm aggregation methodology, while a virtual target based guidance module drives the whole formation towards a desired reference path (further details in [16]). The proposed document improves the performance of the work [15] by presenting the modelling of the two following problems: the positive overvoltage speed (typical constraints of the maritime vehicles) and the saturation speed at a maximum value. Another work [17] proposed an organic computing approach to develop a complete framework for the design (observers) and control of autonomous collaborative robot swarms, with particular emphasis on quadcopters collaborating with each other to perform spatial tasks. The proposed approach has facilitated the adaptability and self-optimization of drone individuals, the optimization of collaborative efforts between drones and an efficient control of the swarm by the human user on several levels of abstraction [18].

Furthermore, a prototype [19] of a USV based on two gas sensors was developed to locate the gas source of an oil spill in the sea. The gas concentration received by the two sensors, applied to a fuzzy logic controller, determines the rate at which each propeller motor approaches the gas target. The result shows that the USV prototype is able to approach and locate the target with average accuracy obtained when searching for the location of the gas source of 90.1%. Thus, a new robotic system swarm [20] was proposed to locate and pick up an oil spill on the surface of the water (ocean, river, lake.). A coordinator determines the position and the center of the spill using a GPS receiver, then a barge carrying the robots moves to the workplace. Depending on the state of the spill, the coordinator can send a swarm of robots to surround and collect the oil spill, then place the barge with oil suction equipment and move it to another location to remove the oil more safely. This new system saves money and time.

In addition, a USV design system [21] was proposed to detect and collect samples of oil spills. The manufactured USV uses a straight-line tracking algorithm with GPS navigation to localize the polluted zone. When it reaches the polluted zone, it activates a sampling mechanism to extract a sample from the water surface and executes the image-based detection algorithm using an automatic learning algorithm to confirm the oil presence. Experiments with this vessel have shown excellent maneuverability, a reliable mechanism for collecting samples and a reasonable accuracy in detecting oil contamination.

On the other hand, an optimal path-planning method for a USV was proposed in [5]. The authors used the grid method modelling for typical obstacles. This grid divides the workspace of the robot (environment) into cells. The white and black cells represent the free space and the obstacle space, respectively. The shortest path is obtained by this frame with the USV eight movements in the grid. The global path planning method used is the ant colony algorithm based on ACO. The roulette method is applied to select the next point at which the USV can reach.

Another ant algorithm ‘Max-Min Ant System (MMAS)’ was studied in [11] to find an optimal or near-optimal path, in which robots should explore the environment at the same time they plan the path. Thus, the authors analyzed the distance traveled by robots during the first iteration of the algorithm to analyze the quality of the solutions obtained. The environment is represented by a topological map. The paths are represented by a sequence of actions that robots should execute to reach the goal. MMAS provided a very good performance and obtained better results (best distance traveled) compared to the best distance traveled obtained by GA and best distance traveled obtained by A* algorithm.

Contrariwise, a real-time in-flight trajectory planner (RTTP) [22] of a fixed-wing UAV was presented for the volcanic monitoring and ash sampling task. The RTTP is based on a GA that allows that finds a a collision-free trajectory with less energy and is adapted to long and high altitude atmospheric conditions over the Volcán de Fuego in Guatemala. In [9], another method for planning pathway is applied, where GA is used to find a sequence of actions for autonomous mobile robots to perform to reach the goal. The robot does not know in advance the disposition of the environment and only has a rough estimate of the starting positions and objective. At first, a set of actions are generated randomly; robots execute these actions. After, their fitness is evaluated by the distance traveled and the Euclidean distance from the goal. Individuals are selected by tournament to breed. Then, a new sequence of actions is generated by applying crossover and mutation operators. The evolution continues only for the sequence of related actions that did not reach the goal. GA has a better average performance and the shortest distances traveled by the solutions returned by GA than the solutions returned by A* and its improvement (C*). In [12], another GA was proposed for the motion planning of heterogeneous holonomic robot swarms. This algorithm consists of a global path planner (GPP) and a motion planner (MP). The GPP algorithm searches for a path that the robot swarm center must move along in the free space of a Voronoi diagram(2D workspace). The MP is a GA based on an artificial potential field. The repulsion keeps robots away from obstacles and the ‘spring’ function maintains the robot swarm within a certain distance from each other. Since GA searches for an optimal configuration with lower potential, the obtained paths are safer. The results of the simulation demonstrated that the proposed algorithm can plan the paths without collision.

This research work aims to provide a new solution to maritime pollution challenges by proposing a hybrid approach based on the two proposed solutions for trajectory planning ‘modified-GA’ and ‘modified-AA’.

3 Proposed approach

This paper presents a new hybrid approach based on the cooperation of air-sea vehicles. This cooperation minimizes the work overload to perform a monitoring and cleaning mission of dirty zones. The unmanned vehicles must plan their paths to achieve their goals in this mission. Thus, the approach proposed in [16] is developed by describing the architecture and constituent entities of the system, the trajectory planning methods, as well as their functioning.

3.1 Architecture of the system

Figure 1 shows the hybrid architecture of the proposed system. It consists of a central unit, a monitoring vehicle to monitor maritime region, a swarm of cleaning vehicles to clean dirty zones, and a recovery vehicles to recover defective vehicles. The central unit is composed of a general coordinator, a base of life and a database. The coordinator general stores and consults the data in the database. It interacts with the base of life and the monitoring vehicle via a communication link of the IEEE.802.11a standard (5000m outside range) of the name Wi-Fi 5. While the WiFi network of the IEEE.802.11b standard (35m-140m indoor range) allows messages to be connected between the monitoring vehicle and the swarm of cleaning vehicles.

Figure 1 Hybrid architecture of the system.
Figure 1

Hybrid architecture of the system.

3.2 Hierarchical role of each vehicle

The decision-making hierarchy of the proposed approach is made up at the first level of a general coordinator. It has the highest decision for the execution of various tasks and the launch and control of unmanned vehicles used, and that are located in the basis of life. The monitoring drone is loaded with a lower decision at a second level. It has the role to supervise and monitor its cleaning vehicle swarms. These cleaning vehicles are located in the third level and are composed by leader vehicles with their cleaning following vehicles. Their objective is to carry out the cleaning operation of the dirty zone according to the energy availability of each member. Each leader of the swarm has two necessary roles. It is responsible for the tasks/characteristics of its followers, and also, it shares (cooperates) with them the cleaning action. The coordinator launches a recovery vehicle to recover the failing vehicles.

3.3 Environment modeling

This section defines the modeling of this work environment along with the set of components. Table 1 summarizes the parameters used.

Table 1

Used parameters for the proposed approach.

ParametersDescription
ThresholdFixed threshold that allows classifying the zone coordinates according to the degrees of cells ’List_Degreecell’.
Thresholdaverage_energycapThreshold of the average energy capacity that has a fixed value and it enabled the determination of the average energy capacity.
Thresholdlow_energycapThreshold of low energy capacity that has a fixed value and it enabled the determination of the low energy capacity.
ListID (IdUSVcz)List of USVcz identifiers composing the swarm.
Listenergy_usv(t)(IdUSVcz, CapenergyCZ)List of the USV energy capacity in instant t during cleaning as well as its identifier.
Listzone(List_Degreecell,List_Positioncell, Positionzone)List of coordinates of the dirty zone.
ListzoneSListzone sorted by the degree of dirt.
Listthreshold_degreeZNbrCZCoordinates list of the dirty zone that is compared with the threshold of dirt compared to the dirty degrees (List_Degreecell). A function that gives the number of selected USVcz by Generalcrd.
PosStart(x,y)Starting position that USVcz can start from the base of life. This position is a Cartesian coordinate (x,y). Each USVcz at its own starting position.
PosEnd(x,y)Final/End position represents the position of arrival of USVcz to the dirty zone. This position is a Cartesian coordinate (x,y). Each USVcz to its own ending position.
PosGol(x,y)Goal position means the next position of USVcz in its move. This position is a Cartesian coordinate (x,y).
ListPosE(x,y)List of Cartisian coordinates (x,y) representing the final positions (to arrive at the dirty zone).
List_tabooPos(IdUSV, PosGol(x,y))List to save positions that are already traversed by USVcz. It contains the identifier of USVcz which has already visited the position PosGol (x,y) where its Cartisian coordinate is the pair (x,y) in the grid.
List_tabooCell (IdUSV, Cell(x,y))List to memorize cells that are already cleaned by USVcz. It is constituted by the identifier of USVcz and its cleaned Cell(x,y). This cell is represented by the Cartesian couple (x,y) in the grid.
List_distCost (linkij, Costij)List of distances between positions that aremarked as an energy cost. It is composed of the link between the position i and j thus its energy Costij.
EnergycapCZEnergy capacity of USVcz.
Listv irtualPos(ListPosS(x,y), PosEnd(x,y))Virtual list which is constructed by a starting position list ListPosS(x,y) and PosEnd(x,y).
Parametersstartup(M)(Idregion,Positionregion, Pathregion)Triplet of start parameters for each UAVmr which represents the identifier, position, and trajectory of a region.
Parametersstartup(C) (Idregion, Idzone, IdSUPMR, IdLeaderCZ, Positionzone, PosS tart(x,y), PosEnd(x,y), ListPosE(x,y))Triplet of the start parameters for each USVcz which represents the identifier of its region, zone, supervisor, leader and the position of zone with PosStart(x,y) and PosEnd(x,y) and ListPosE(x,y).
Parameterscleaning (PosUSVg, Cellcz, Idregion, Idzone, Positionzone, Trajectoryzone, IdSUPMR, IdLeaderCZ)Cleanup parameters for USVcz that replaces USVcz(discharge). This list contains: the position of USVcz in the grid, the cell to be cleaned, the identifier, the position and the trajectory of zone, the identifier of region, Supmr and Leadercz.
Listcharacteristics (Idzone, IdUSVCZ, DurED1, ConsED1, DurED2, ConsED2, DurEC, ConsEC)List of USVcz characteristics where it contains the identifier of a zone and a USVcz, the duration and the energy consumption of displacement of the base of life towards the dirty zone (DurED1, ConsED1), the duration and the energy consumption of displacement in the dirty zone (DurED2, ConsED2) and the duration and the energy consumption of cleaning (DurEC, ConsEC).
  1. Set of tasks: five high level tasks are defined and used by the general coordinator, the monitoring and cleaning vehicles:

    1. Allocating task (ta) represents the task of allocating unmanned vehicles to different regions r and dirty zones z;

    2. Monitoring task (tmr) represents a task of monitoring a region r;

    3. Cleaning task (tcz) represents the task of cleaning a zone z;

    4. Supervising cleaning task (tsz) represents the task of supervising the cleaning of a zone z;

    5. Launching task (tl) represents the launching spot of the different previous tasks (monitoring, cleaning, supervising cleaning and allocating tasks).

  2. Set of vehicles: different vehicles with their related roles are described as follows:

    1. UAVmr: monitoring, homogeneous and semi-autonomous aerial vehicle; this vehicle incorporates a camera, an ultrasonic sensor, a GPS (Global Positioning System) and an autopilot software; it features a speed and an energy capacity that allows it to complete the following roles/tasks: monitor the regions, dirty zones, and supervise the cleaning vehicles swarm; ask / inform the task leader; launch / return the data and results to the general coordinator;

    2. USVcz: cleaning, homogeneous and semi-autonomous surface vehicle; it has the same hardware and features as UAVmr except it does not embed a camera; USVcz is responsible for: cleaning the dirty zones; following / requesting tasks and informing / returning the data and results to its leader;

    3. Leadercz: cleaning, homogeneous and semi-autonomous surface vehicle; this vehicle is similar to USVcz in hardware and software components; it allows to: cooperate with followers (USVcz) for cleaning mission; send the requests for its followers; receive / save the characteristics of each follower and save its features; inform / return the data and results to its supervisor;

    4. Vehiclerec: it is a special vehicle named recovery vehicle; it is similar as to USVcz in hardware and software components; it allows the recovery and the return of faulty vehicles (out of order) towards the base of life (detailed description of Vehiclerec is presented in [23]).

  3. Set of agents: a description is provided for each used agent:

    1. Generalcrd: General coordinator is represented by a laptop that contains a coordination software, guided by a human operator; it is responsible for the following: the base of life, data of the regions and the dirty zones; use (treatment)/storage of data in the database; launch of the tasks / missions and allocate tasks to vehicles;

    2. Leadercz: Leader vehicle is a USVcz that has two roles: it is an intermediary between the supervisor and USVcz swarm, and also cooperates in the cleanup operation;

    3. USVcz(discharge): Cleaning vehicle in discharge state is a cleaning vehicle, that has not yet completed its task and energy capacity are low during cleaning;

    4. USVcz(free): Cleaning vehicle in free state is a cleaning vehicle that has completed its task;

    5. USVcz(prepared): Cleaning vehicle in prepared state is a cleaning vehicle prepared in the base of life by the Generalcrd which will replace USVcz(discharge);

    6. Supmr (USVcz_discharge): Supervisor of USVcz (discharge) is the surveillance vehicle (USVcz) of the cleaning vehicle in discharge state;

    7. Supmr (USVcz_free): Supervisor of USVcz (free) is the surveillance vehicle (USVcz) of the cleaning vehicle in free state;

    8. Supmr (USVcz_prepared): Supervisor of USVcz (prepared) is the surveillance vehicle (USVcz) of the cleaning vehicle in prepared state;

    9. Leadercz(USVcz_discharge): Leader of USVcz (discharge) is the leader of the cleaning vehicle in discharge state;

    10. Leadercz(USVcz_free): Leader of USVcz (free) is the leader of the cleaning vehicle in free state;

    11. Leadercz(USVcz_prepared): Leader of USVcz (prepared) is the leader of the cleaning vehicle in prepared state.

  4. Set of regions: the monitored maritime space is divided into maritime regions; the region is composed of two sub-spaces: an atmosphere sub-space where UAVmr can be found, and a maritime sub-space with the swarm of USVcz, Vehiclerec, base of life and dirty zones.

  5. Set of base of life: it is a zone (can be a boat, ship or an island) to store a fixed number of UAVmr, USVcz and Vehiclerec.

  6. Set of database: these are basics for storing and saving all the data and features of the maritime space as well as the different unmanned vehicles used.

  7. Set of dirty zones: with water pollution, for example oil slicks or plastic waste; the proposed metric in this work is the degrees of dirt for each zone with four types: strong dirt, average-strong dirt, average dirt and low dirt; each zone is characterized by a list ‘Listzone’ which delimits its borders by the coordinates; they are composed by the list the degrees of dirt ‘List_Degreecell’, list of cell positions of this degrees ‘List_Positioncell’ and they are attached to a zone by ‘Positionzone’.

3.4 Hybrid approach with two trajectory planning solutions

This section describes the key steps of the proposed hybrid approach with a proposal for tailored solutions. The first solution is based on a genetic algorithm (GA), and the second is based on an ant algorithm (AA). To this end, the approach is based on two essential steps: monitoring and cleaning. Both solutions are applied in the cleaning step. Figure 2 illustrates a structure of the proposed approach.

Figure 2 Structure of the proposed hybrid approach.
Figure 2

Structure of the proposed hybrid approach.

3.5 Step 1: Monitoring

This step presents the actions of the UAVmr monitoring phases:

3.5.1 Phase 1: monitoring setup

The monitoring step is performed, for example, twice a week in the maritime region to be monitored. The general coordinator Generalcrd prepares the monitoring drones according to the region numbers, allocating a UAVmr for each region. In addition, Generalcrd checks periodically the maritime space statistics that are saved in the database. If it finds a statistic region that contains a high percentage of dirty zones in a certain period, it launches a UAVmr for a full day to monitor this dirty zone.

3.5.2 Phase 2: monitoring execution

Generalcrd triggers the monitoring step according to the following actions:

  1. Prepare each UAVmr with startup parameters Parametersstartup(M) (Idregion, Positionregion, Pathregion), the atmosphere map explored, the energy (battery charged) and the associated speed before starting.

  2. Each UAVmr is launched from the base of life to the end position according to the assigned Pathregion. It follows this path with a rectilinear movement [16] to reach its region. When UAVmr arrives at its region, using the explored map (a discrete grid 2D) of the atmospheric part of the region, it moves, captures and records the data of maritime sub-space in Listzone(List_Degreecell, List_Positioncell, Positionzone) following a swipe movement [16]. The collection of data is based on a discretized map (grid 2D) by the UAVmr using its sensor (a camera and an ultrasonic).

  3. Once the maritime level data collection is complete, UAVmr sorts the collected list and saves it in a ListzoneS. Then, it compares the List_Degreecell of ListzoneS with a fixed threshold. After the comparison, it saves the result in Listthreshold_degreeZ and sends it to Generalcrd.

Algorithm 1: Calculate the needed number of USVCZ

Inputs

Listthreshold_degreeZ [C]: list which contains the degree of dirty cells of a zone compared with threshold, where C represents the length of this list; M: represents the number of USVCZ in base of life (constant).

Outputs

y: the solution variable to find the number of USVCZ ;

Listaverage [A] : list of average of Listthreshold_degreeZ , where A represents the length of Listaverage [A];

ListX[X]: list of value x , where X represents the length of ListX[]; NbrCZ [U] : list which contains the USVCZ numbers, where U represents the length of NbrCZ [U];

begin

for all (Listthreshold_degreeZ received) do

calculate average(Listthreshold_degreeZ );

save Listthreshold_degreeZ in Listaverage ;

end for

calculate min(Listaverage );

%calculate the solution variable to find the number ofUSVCZ

(int) y=0, sum=0, X=A;

for all ((int) x=0 to X) do

ListX[X] Listaverage[a]/min;

sum=sum+ListX[X];

end for

calculate the solution of equation (y) sum sum * y;

y = M/sum;

for all (x ListX[A]) do

NbrCZ [x] ← y*ListX[x];

end for

3.6 Step 2: Cleaning

This step is organized in three phases: cleaning setup, execution and cleaning finalization.

3.6.1 Phase 1: cleaning setup

The two proposed solutions (modified-GA and modified-AA) are applied exactly in this phase. In addition, they guide the USVcz swarm to execute the moving phase to dirty zones. Before applying the two solutions, Generalcrd analyzes the received data (List_thresholddegreeZ) from each UAVmr. Then, it determines the USVcz number containing the swarm for each dirty zone. This action is described by Algorithm 1. Then, the main phases of the two proposed solutions are presented so that the USVcz swarm can plan its way to its dirty zone.

3.6.1.1 Solution 1: modified-GA trajectory planning

This phase is presented as the first solution modified to the trajectory planning problem. Different actions of this solution are mentioned so that the USVcz swarm selected can build its trajectory towards its dirty zone.

  1. Genetic algorithm setup: the proposed GA is inspired by the algorithm presented in [24]. In this GA, the USVcz swarm must search for an optimal trajectory between the starting position (the base of life) and the goal (the dirty zone). Table 2 presents a comparative table of the proposed approach with the work of [24] in [16].

    1. Environment modeling: the environment modeling depends on the map of the discretized region (metric map) by Supmr. The workspace is discretized by a square grid G which is composed of square cells. A node is located inside each cell to facilitate the movement of USVcz. These nodes build a dynamic graph where the arcs are presented by Rij connection links. Rij between two neighboring cell-nodes represents the distance between two positions (Figure 3). This distance is represented by the energy value Eij that USVcz can consume in the displacement. Each cell-node ith represents a free / occupied position by a position or a non-solid obstacle in the environment. These positions are identified by Cartesian coordinates (x,y) in a 2D plane. These positions have a maximum of eight links (Rij) with the neighboring positions jth.

    2. Trajectory planning method: Generalcrd assigns a PosStart(x,y) and the list of end positions ListPosEnd(x,y) to each USVcz. This list sets the positions to arrive at the dirty zone. Then, the trajectory, traveled by USVcz from a PosStart(x,y) to a PosEnd(x,y) passing through all accessible positions and avoiding obstacles, is called the global trajectory planning. To obtain this global trajectory, it should be divided into a mini-trajectory; the latter must not exceed the sensor range of USVcz (an ultrasonic sensor), as shown in Figure 4. The range of the sensor represents a detection of the region Rs of s * s boxes that allows USVcz to capture its neighboring positions relative to its current position. A USVcz can move by one step between cells. The mini-trajectory contains PosStart(x,y) and PosGol(x,y). If PosGol(x,y) is equal to one of ListPosEnd(x,y), then USVcz has arrived in the dirty zone. The mini-trajectory contains PosGol(x,y) which are occupied by USVcz when it is moved. The others remain un-browsed until they are taken into account during the next planning. The aim is to obtain an efficient global trajectory. To this end, the mini-trajectory should be effective and with a short distance, less obstacle and a minimum of energy consumed.

    3. Evolutionary approach: an evolutionary approach based on GA is proposed to minimize the energy consumption, obstacle and trajectory distance. GA helps the USVcz find an efficient trajectory from the PosStart(x,y) to PosEnd(x,y) (further details in [16]).

    4. Encoding and generation of initial population: after the environment modeling is finished, each node has its own number. The gene is made of one part which represents the number nodes. This gene corresponds to a position of USVcz. The chromosome represents a mini-trajectory which contains a number of genes, the latter should belong to the rayon of the sensors. The population has a fixed length of individuals and each individual has a sequence of initial positions (cell-node). The mini-trajectory planning is random by choosing neighboring positions in the known environment. As a result, individuals have their sequences of positions (mini trajectory), where a mini trajectory is chosen to execute it by USVcz (more clarification found in [16]).

    5. Fitness Function and Selection: fitness function is necessary to know the details and solution of the problem. Two parameters are taken into consideration to evaluate the fitness of the mini-trajectories: the total distance of mini-trajectory and the direction cost for each USVcz. An appropriate fitness function of mini-trajectory (i) is constructed as follows:

      (1)Fi=ADistTrajectory(i)+BCostDir(i)
      (2)CostDir(i)=Directcost+Leftcost+Rightcost

      where, A and B are two equilibrium parameters (constant numbers) and DistTrajectory(i) and CostDir(i) are the distance of the mini-trajectory (i) and the direction cost for each USVcz respectively. DistTrajectory(i) is calculated by the sum of each distance between two cell-nodes in which this distance is represented by a value of energy. CostDir(i) is calculated according to the direction of USVcz when it moves to another node. It has three directions: direct direction (Directcost) where USVcz moves to another position in the same direction; right/left direction (Rightcost/Leftcost) where it turns to the right/left of its position to get to another position.

    6. Genetic operators: new position sequences (new individuals) are created by applying crossover and mutation operators. Crossover is a performed positions sequence provided by two parents. These parents (two mini-trajectories) are selected by the tournament, where they (the individuals) are chosen at random and who with a low fitness value becomes a parent. A one-point crossover technique was chosen for this approach; two children are then added to the population. Figure 5 shows an example of a crossover operator, where the crossover point is the middle of the trajectory of parent 1. Then, child 1 takes the first part of the parent 1 chromosomes plus the second part of the parent 2 from the crossover point. Thus, child 2 takes the first part of parent 2 and the second part of parent 1. Therefore, two new mini-trajectories are provided. The mutation defines a quantity of genes that build a problem in the trajectory. The gene is replaced by one of the neighbor genes of its previous gene that are also randomly selected. Figure 6 shows the mutation operation on child 1 of the previous example. At each generation, applied elitism can be created by new individuals (children) of length l who have a low fitness to replace previous individuals (parents). Each new position sequence is executed by an associated USVcz, so that the fitness value of each new individual is calculated.

  2. Modified-GA based trigger process: when Generalcrd chooses USVcz swarm, it sends the Listidu sv(IdUSVCZ) to their Supmr. In return, Supmr sends its discrete maritime exploration map. Generalcrd broadcasts a set of parameters to the selected swarm, as shown in the sequence diagram of Figure 7.

Table 2

Displacement-cleaning energy consumption for a zone with a strong degrees of dirt.

Numbers of USVczCEC_GACEC_AA
3292,25289,75
4347,15344,65
5331,15451,7
6353,9354,2
7404,3409,6
Average gain: 0.4%Minimum gain: 0.5%Maximum gain: 1.2%
Figure 3 Environment modeling of the modified-GA.
Figure 3

Environment modeling of the modified-GA.

Figure 4 Trajectory planning method.
Figure 4

Trajectory planning method.

Figure 5 Crossover operator.
Figure 5

Crossover operator.

Figure 6 Mutation operator.
Figure 6

Mutation operator.

Figure 7 Sequence diagram of the ’modified-GA based trigger process for USVcz swarm’.
Figure 7

Sequence diagram of the ’modified-GA based trigger process for USVcz swarm’.

After, Generalcrd launches the execution of GA and each USVcz of the swarm plans to move from the above mentioned steps of GA to the dirty zone.

3.6.1.2 Solution 2: modified-AA trajectory planning

This phase is presented as the second suitable solution for the trajectory planning problem.

Different actions of this solution are mentioned so that the USVcz swarm selected can build its trajectory towards its dirty zone.

  1. Ant algorithm setup: this solution is based on an ant algorithm proposed in [6, 25]. These algorithms show the steps of modeling ants’ behavior in the environment. To this end, the proposed modified-AA can model the behavior of a USVcz swarm to find an optimal trajectory between the base of life and the dirty zone. In addition, the discretized grid G is composed of cells that contain positions. These positions are presented as cities. Each city ith represents a free / occupied position by a USVcz agent. These cities are identified by Cartesian coordinates (x,y) in a 2D plane. Cities ith can have connection links (edges) Rij between neighboring positions jth. Rij represents the distance between cities (Figure 8). This distance is represented by an energy cost Eij that a USVcz agent will consume in the displacement between the cities.

    Based on the proposed algorithm, named ‘Modified-Ant Algorithm’, each agent USVcz is placed in a starting city. USVcz moves from one city to another using the connection links between cities towards the goal. ui(t) is the vehicle number in city i at time t and U=i=0mui(t)the total number of vehicles. The cities have three positions known by the USVcz: starting city PosStart(x,y), goal city PosGol(x,y) and final city PosEnd(x,y). If the end city PosEnd(x,y) equals the goal position PosGol(x,y), then the USVcz has arrived at the dirty zone. Each USVcz agent has the following characteristics:

    1. It deposits a pheromone trace on Rij when it moves from city i to city j;

    2. It chooses the destination city according to a probability that depends on the distance between this city and its position and the amount of pheromones present on the edge (transition rule);

    3. To pass only once through each city, USVcz cannot go to a city that has already been crossed, that’s why USVcz must have a memory ‘List_tabooPos(IdUSV, PosGol(x,y))’.

Figure 8 Environment modeling of the modified-AA.
Figure 8

Environment modeling of the modified-AA.

The traces of pheromones are modeled by the variables τij(t) which give the intensity of the trace on the trajectory (i, j) at time t. The transition probability from city i to city j by the agent ui(t) is given by:

(3)Pij=[τij(t)]α.[Vij(t)]βlLu(i)[τil(t)]α.[Vil(t)]β,ifjLu(i)0,else

where, Lu(i) represents the List_tabooPos of ui(t) located on the vertex i and Vij represents a measure of visibility that corresponds to the inverse of the distance between cities i and j. This list is represented by:

(4)Vij1jdij

where, dij is the distance between the city i and j, which is presented by the Eij in the array List_Cost. Then α and β are two parameters for modulating the relative importance of pheromones and visibility. The update of the pheromones is done once all the ants have passed through all the cities:

(5)τij(1ρ)τij+u=1mΔτiju

where ρ is a coefficient the evaporation of traces of pheromones. Then Δτijurepresents the link reinforcement (i, j) for ui(t):

(6)Δτiju=QLu,if USV passed through the arc (i, j)0,else

where Q is a constant and Lu is the length of the trajectory traveled by ui(t) (the sum of the energy costs consumed during the travel between cities).

  1. Running of ‘Modified-AA’ algorithm:

    Generalcrd prepares a virtual list of List_virtualPos(ListPosS(x,y), PosEnd(x,y)). This list is constructed by a starting position list ListPosS(x,y) and an ending position PosEnd(x,y) (the arrival at the dirty zone). Generalcrd assigns a PosStart(x,y) for each agent USVcz of the selected swarm, and the PosEnd(x,y) is shared in this swarm. Generalcrd launches Algorithm 2 to find the best trajectory that will apply to the swarm. The flow is started by initializing the transition trace τij(t) (3). An interval of time is proposed to assess the improvement of the trajectories built. Each ui(t) will build its trajectory (Pathu(t)) from its PosStart(x,y) to the PosEnd(x,y). This construction is made based on the transition rule (3). The agent ui(t) detects its detection region via its ultrasonic sensor to identify its neighboring cities. From the maximum transition probability Pij(t) that was computed, its next destination city is known. When the trajectory is complete, its length Lu(t) is calculated. This trajectory is saved in a ListPath_UT list. At each end of the time lapse, the τij(t) (rule (5)) is updated. After, the best trajectory found in ListPath_UT is selected based on the maximum value of Pij(t). The best trajectory of t is saved in a list PathFinal_UT. When t = tmax, the best trajectory Best_pathu is selected of all t turns among the trajectories found in PathFinal_UT. This trajectory is selected based on its maximum value of Pij(t).

  2. Modified-AA based trigger process: when

    Generalcrd chooses the USVcz swarm, it sends the Listidu sv(IdUSVCZ) to its Supmr. In return, Supmr sends its discrete maritime exploration map. Generalcrd broadcasts a set of parameters to the selected swarm, as shown in the sequence diagram of Figure 9. After, Generalcrd sends Best_pathu to the swarm after changing the starting position of each USVcz. The latter moves together in the grid following the Best_pathu. Then, the first USVcz is started from the PosStart(x,y) of the trajectory, then the second starts from the first position of the first USVcz, and so on. Each USVcz follows its neighbor USVcz. When the first USVcz arrives at PosEnd(x,y), every USVcz except the first one checks its position to see if it is one of the positions found in ListPosE(x,y) except the PosEnd(x,y) of the first USVcz. Otherwise, each of these USVcz performs a small function to arrive at one of the end positions (Algorithm 3). When all USVcz are found in their end positions, Generalcrd changes the PosEnd(x,y) of each USVcz in the startup parameters.

Figure 9 Sequence diagram of the ‘modified-AA based trigger process for USVcz swarm’.
Figure 9

Sequence diagram of the ‘modified-AA based trigger process for USVcz swarm’.

Algorithm 2: Modified - Ant Algorithm

Inputs

ListID_USV [u]: list which contains the ID of USV, where U represente the length of ListID_USV [].

Lu(t): length of path.

P_ij(t): transition probability.

t0: initial time.

tmax : maximal time.

n: numbers of cities (positions).

m: numbers of USV.

Outputs

Pathu(t): path built by USV.

ListPath_UT: list of Pathu(t).

Best_pathu: best path found in ListPath_UT.

PathFinal_UT: list of Best_pathu.

Best_pathTu: best path selected.

begin

(double) T_ij = (double)T_0 (i, j) 1,...,n

for (T_0 to t_max) do

for all ((int) u ∈ ListID_USV ) do

build Pathu(t) with the transition rule (2.1)

calculate the length Lu(t) of this path

save Pathu(t) in ListPath_UT with corresponding P_ij(t).

end for

for all (Pathu(t) ∈ ListPath_UT) do

find Best_pathu with a maximum (double) P_ij(t). save Best_pathTu in ListPathU T with corresponding P_ij(t). update τij (t) with the rule (2.2).

end for

end for

for all (Best_pathTu ∈ ListPath_UT) do

find Best_pathu with a maximum P_ij(t).

end for

Algorithm 3: Position adjustment of USV

for ((int) u ∈ ListID_USV ) do

while ((int) PosEnduListPosE) do

search if PosEndu != occupied by another u;

search nearest PosGol in neighboring positions;

if ((int) PosGol == PosEndu) then

PosEndu PosGol;

end if

end while

end for

3.6.2 Phase 2: cleaning operation

This phase allows the USVcz swarm to move into the dirty zone and clean it. The maritime space is discretized in square grid (G). Each box of G can contain an object (a dirty cell / a clean cell). Objects are points in a numerical space with M dimensions; these objects to be partitioned are positioned. USVcz can move in G and perceive a detection region Rs in their neighborhood (Figure 4). These USVcz can clean the dirty cell type objects. To this end, Algorithm 4 applies the proposed approach with the two solutions. Using this algorithm, the swarm can move in the dirty zone and clean its dirty objects. This phase is started when the swarm arrives at its dirty zone. Generalcrd stops the execution of modified-GA and modified-AA. Subsequently, Generalcrd selects a Leadercz from the USVcz composing the swarm, and at the same time shares this information with the other USVcz. This leader has a very high energy capacity compared to other USVcz. After, Generalcrd launches Algorithm 4 on the swarm and at the same time Leadercz launches the recording of the characteristics of himself and its followers. The USVcz of the swarm follow the algorithm so that they can properly position and move between the clean cells, select the cells to be cleaned after-wards, and share their positions between them.

3.6.3 Phase 3: cleaning finalization

This phase identifies the end of the cleaning step and collects the current characteristics of USVcz for each proposed solution, and has three cases:

  1. Case 1: The cleaning task is completed. When the USVcz finishes its cleaning task, it returns to the base of life with a message of acceptance received by its Leadercz (further details in [16]).

  2. Case 2: The cleaning task is not complete and EnergycapCZ is average. In this case, two situations are available:

    1. The first situation: if EnergycapCZ of USVcz is greater than a Thresholdaverage_energycap, i.e. its energy capacity is average. So, its Supmr finds a USVcz(free) in the swarm of the same zone (further details in [16]).

      Algorithm 4 Cleaning Operation

      Inputs

      ListCrd_USV [sizeU]: list which contains the cartesian coordinate of each USV (ux , uy ), where sizeU represente the length of ListCrd_USV [sizeU].

      ListCrdthresholddegreeZ[sizeD]: list which contains the cartesian coordinates of the dirty cells of zone (dx , dy ), where sizeD represente the lenght of this list.

      Outputs

      (NewUx , NewUy ): cartesian coordinate pair that represents the new position of each USV.

      ListTabooCelU[sizeC]: list which represent the memory of dirty cells that are already cleaned by USV.

      ListNearbyCrdU[sizeN]: list which contains the neighboring coordinates (vx , vy ) of USV (ux , uy ), where sizeN represente the length of

      ListNearbyCrdU[sizeN].

      ListCrd_USV [sizeU].

      begin

      while ((int) u < sizeU && (int) d < sizeD) do

      for all ((int) d ∈ ListCrdthresholddegreeZ[sizeD]) do

      calculate the distance between (ux , uy ) and (dx , dy );

      end for

      select couple (dx , dy ) which it has a minimal distance with (ux , uy );

      if ((uxdx==0) && (uydy==0)) then

      NewUx = dx; A

      NewUy = dy; B

      update((NewUx , NewUy),ListCrd_USV[sizeU]); C

      delete((dx , dy);ListCrdthresholddegreeZ[sizeD]); D save((NewUx , NewUy),ListTabooCelU[sizeC]); E

      else if ((uxdx==0) && (uydy==1)) then execute A, B, C, D and E instructions;

      else if ((uxdx==1) && (uydy==0)) then

      execute A, B, C, D and E instructions;

      else

      find nearby positions((ux , uy ); ListNearbyCrdU[sizeN]);

      for all ((vx , vy ) && ListNearbyCrdU[sizeN]) do

      if ((vx , vy)!= occupied_another (ux , uy ) && (vx , vy)!= dirty) then calculate the distance between (ux , uy ) and (vx , vy );

      end if

      end for

      select couple (vx , vy ) which it has a maximal distance with (ux , uy );

      NewUx = vx ;

      NewUy = vy ;

      update((NewUx , NewUy ), ListCrd_USV [sizeU]);

      end if

      u++;

      if ((u==sizeU) && (d!=sizeD)) then

      u=0;

      end if

      end while

    2. The second situation shows the case where there is not a USVcz(free) in the same zone. So, USVcz(discharge) informs its Leadercz by its Listenergyusv(IdUSVCZ, EnergycapCZ). Leadercz(USVcz_discharge) sends Listenergyusv and Parameterscleaning(PosUSV, Cellcz, Idregion, Idzone, Positionzone, Trajectoryzone, IdUAVMR) to its Supmr. After a waiting deadline, if Supmr does not receive another message (a detection message of USVcz(free) in the other zone in the same region by Leadercz(USVcz_free)) before exceeding this deadline, then it passes to the third situation. Otherwise, Leadercz(USVcz_free) sends Listcharacteristicsu svs with Listenergyusv of their USVcz(free) to Supmr. Supmr processes the received message and selects USVcz(free) that has a higher energy capacity. So, if it does not find any competent USVcz then it passes to the third situation. Otherwise, Supmr informs its Leadercz(USVcz_free) by USVcz(free) with the complete cleanup parameters (Supmr changes the new position of USVcz(free), Idzone and new cell that USVcz(free) will clean it with the same parameters Idregion, Positionzone, Trajectoryzone, IdUAVMR). Leadercz(USVcz_free) returns the received message to its USVcz(free). Leadercz(USVcz_free) waits until the power capacity of USVcz(discharge) becomes low to launch the USVcz(free).

    3. The third situation is illustrated by Algorithm 5. This situation shows the case where Supmr finds a USVcz(free) that is assigned to dirty zones in the other region.

    4. The fourth situation is presented where there is not a free and competent USVcz to complete the task of USVcz in discharge state. So, Supmr(USVcz_discharge) sends a message to the Generalcrd to inform / require it of the need for a USVcz with Parameters_cleaning. It prepares a USVcz in the base of life with the filled Parameters_cleaning. After, it sends the identifier of USVcz(prepared) with the cleaning parameters to Supmr (USVcz_discharge). This latter sends this identifier to Leadercz(USVcz_discharge) expecting the message of the energy capacity of USVcz(discharge) becomes low.

  3. Case 3: The cleaning task is not complete and EnergycapCZ is low. This case is realized when the energy of USVcz(discharge) becomes low; that is, the energetic capacity (EnergycapCZ) of USVcz is greater than a Thresholdlow_energycap (following the situations mentioned above). USVcz(discharge) sends this information to its supervisor through its leader (all situations except the first situation: USVcz(discharge) sends this information right to its leader and the leader informs it to return to the base of life). Then, Supmr(USVcz_discharge) sends a message (Inform launch):

    1. Directly to Leadercz(USVcz_free) to USVcz(free): if this vehicle is owned in another zone in the same region (second situation);

    2. Generalcrd to another Supmr(USVcz_free): run the USVcz(free) and prepare it with the cleaning parameters to calculate its trajectory and swim to its new dirty zone and clean it; Generalcrd broadcasts this information to other Supmr (third situation);

      Algorithm 5: Third Situation (3)

      for all ((int)USV swarm) do

      if CleaningTask_USV =6nul and ErgyCap_USV ≥ Threshold_Average then

      send(USVdischarge ), (int) Leader(USVdischarge ), ’ErgyCap_USV and

      Parameters_cleaning’);

      save(Leader(USVdischarge ), ’ErgyCap_USV and

      Parameters_cleaning’);

      send(Leader(USVdischarge ), (int) Sup(USVdischarge ), ’ErgyCap_USV and Parameters_cleaning’);

      save(Sup(USVdischarge ), ’ErgyCap_USV and Parameters_cleaning’); send(Sup(USVdischarge ), (int) GeneralCrd, ’Need a USV(free) and

      Parameters_cleaning’);

      broadcast(GeneralCrd, Supmr,’Need a USV(free)’);

      while (time != nul) do

      for all ((int) USV AllDirtyZone(others regions)) do

      if (USV == free) then

      inform(USV (free), (int) Leader(USVfree ),

      ’CleaningTask_USV = nul’);

      save(Leader(USVfree ), USV(free), ’List_USV(free)’);

      end if

      end for

      for all ((int) Leader(USVfree ) AllDirtyZone(same region)) do

      send(LeaderUSVfree ), (int) Sup(USVfree ), ’List_USV(free) and

      ListCharacteristics_usvs’);

      save(Sup(USVfree ), ’List_USV(free) and

      ListCharacteristics_usvs’);

      end for

      for all ((int) Sup(USVfree ) others regions) do

      send(Sup(USVfree ), GeneralCrd, ’List_USV(free) and

      ListCharacteristics_usvs’);

      end for

      send(GeneralCrd, Sup(USVdischarge ), ’List_USV(free) and

      ListCharacteristics_usvs’);

      analyze(Sup(USVdischarge ), ’List_USV(free) and

      ListCharacteristics_usvs’);

      if (List_USV(free) =6nul) then

      select(Sup(USVdischarge ), USV_Competent);

      requestfill(Sup(USVdischarge ), (int) GeneralCrd,

      ’Parameters_cleaning’);

      fill(GeneralCrd, ’Parameters_cleaning’);

      send(GeneralCrd, Sup(USVdischarge ), ’Parameters_cleaning’);

      broadcast(GeneralCrd, Sup(USVfree ), ’USV_Competent and Parameters_cleaning’);

      send(Sup(USVfree ), Leader(USVfree ), ’Parameters_cleaning’);

      inform(Leader(USVfree ), USV_Competent, ’Wait’);

      else

      pass(Sup(USVdischarge ), Situation4);

      end if

      end while

      pass(Sup(USVdischarge ), Situation4);

      end if

      end for

    3. Generalcrd to USVcz(prepared): launch USVcz(prepared) which is in the base of life and to prepare it with the cleaning parameters; it can calculate its trajectory and swim to its new dirty zone and clean the remaining cells (fourth situation); Supmr(USVcz_discharge) informs USVcz(discharge) through its Leadercz(USVcz_discharge) to return so that it can swim from its zone to the base of life (and to charge) (all situations except the first situation). Leadercz(USVcz_discharge) sends Listcharacteristics_usvs of USVcz(discharge) to its supervisor and to Generalcrd for the record. Supmr(USVcz_discharge) informs the Leadercz(USVcz_free) to modify Listcharacteristics_usvs (second and third situations) or prepare it for USVcz(prepared) (fourth situation). Finally, Leadercz(USVcz_free) informs its USVcz(free) to start the cleanup and modifies at the same time the Listcharacteristics_usvs of USVcz(free) (first situation).

4 Logical formalization of the proposal

4.1 Conceptual model for planning

A conceptual model is a simple theoretical device to describe the main elements of a problem [26]. Most of the planning approaches described in [27] rely on a general model, which is common to other areas of computer science, namely the model of state-transition systems (also called discrete-event systems) [16, 26, 27]. The technical words of this formalizations (further details in [16]) are given in a general way.

Example 1. This example shows the state transition systems defined for three domains: UAV - Monitoring (or UAV -Mdomain applied to UAVmr), Swarm (USV) - Cleaning (or SUSV-C domain applied to USVcz) and USV (Substitute) - Cleaning (or USVS-C domain applied to USVcz). These domains are presented by the following:

  1. ‘UAV - Monitoring’ domain: Figure 10 shows a state transition system for a region involving two locations, a dirty zone, a base of life (for example: a boat) and a UAVmr. The set of states is {s0, s1, s2, s3} and the set of actions is {stayinbase, flaputbase, move1start-monitor, move2end-monitor, discover, undiscover}.

Figure 10 A state transition system for the UAV-M domain.
Figure 10

A state transition system for the UAV-M domain.

  1. ‘Swarm (USV) - Cleaning’ domain: The system of region (Figure 11) involves three locations, two dirty zones, a base of life, object of the crane type for picking up, putting down and releasing unnamed vehicles. The set of states {s0, s1, s2, s3} and the set of actions is {take, put, start-clean, end-clean, move1, move2}.

Figure 11 A state transition system for the SUSV-C domain.
Figure 11

A state transition system for the SUSV-C domain.

  1. ‘USV(substitute) - Cleaning’ domain: The system presented in Figure 12 is similar to the previous system. However, the difference is the use of a replacement cleaning vehicle (in free / prepared state), which will replace a USV in discharge state. The set of states is {s0, s1, s2, s3, s4, s5} with {takeDmove2, putDputD, moveD1start-clean, moveD2endclean, moveD1move2, moveD2move1, move1, move2}.

Figure 12 A state transition system for the UAVS-C domain.
Figure 12

A state transition system for the UAVS-C domain.

4.1.1 A running example of ’ UAV-M ’, ’ SUSV-C ’ & ’ USVS-C ’

The planning procedures and techniques are illustrated in an example of simple nontrivial execution that include three domains, namely UAV-M, SUSV-C and USVS-C. These domains complement each other. An abstract version of these domains can be defined from ten complete sets of constant symbols [16], namely a set of: regions (Rr), locations for each region (Llr), base of life (Bbr), dirty zones (Zzl), monitoring vehicle (UAVmr), cleaning vehicle swarm (USVcz), cleaning vehicle in discharge state (USVDcz), cleaning vehicle in free state (USVFcz), cleaning vehicle in prepared state (USVPcz) and a set of cranes (Cnb).

Thus, the topology of these domains is noted using the instances of predicates [16]: adjacent(E, E’) where localization E = {Llr, Rr} is adjacent to E = {Llr, Rr}, belong (C, L) where crane C = Cnb belongs to location L and belong (B, R) where a base of life B = Bbr belongs to region R=Rr. Also, the current configuration of the domains is denoted using instances of the following predicates, which represents the relationships that change over time [16], namely at(NAME, E) where NAME = NAME1{UAVmr, USVcz} and NAME2{USVFcz, USVPcz, USVDcz, SUSVcz}, occupied(L), start-clean (NAME, Z), end-clean(NAME, Z), start-monitor(NAME, R), end-monitor(NAME, R), replace(NAME, NAME) notreplace (NAME, NAME), discover(NAME, Z), undiscover(NAME, Z), supervise(NAME,NAME), notsupervise(NAME, NAME), holding(C, NAME), stayinbase(NAME, B), flapoutbase(NAME, B). Possible actions for this domains [16] can be: start-clean(NAME, Z), end-clean(NAME, Z), start-monitor(NAME, R), end-monitor(NAME, R), discover(NAME, R, Z), undiscover(NAME, R, Z), stayinbase(NAME, B), flapout-base(NAME, B), move(NAME, E1, E2), moveD(NAME, E1, E2), take(NAME, C, R), takeD(NAME, C, R). The action ‘moveD’ is executed in parallel with the action ‘start-clean’, ‘end-clean’ and ‘move’. The actions ‘takeD’ and ‘putD’ are executed in parallel with the action ‘move’.

4.1.2 Representations for classical planning

The classical planning problems are presented in three differentways [26], namely: i) Set theoretic representation, ii) Classical representation, iii) State-Variable representation. This work focuses on the second representation (classical) to apply its planning on the proposed approach.

Example 2. This example illustrates a classical representation of the scenario ‘UAV -M domain’ and ‘SUSV-C domain combined with USVS-C domain’ which are described in Example 1:

  1. For the UAV-M domain: a UAV-M planning domain is formulated with a drone (UAV11), a region (R1), a base of life (B11), three locations (L11, L21, L31), six dirty zones (Z11, Z42, Z63, Z22, Z32, Z53) and five vehicles (USV11, USV31USV26, USV46, USV66). The set of constant symbols is given by {UAV11, R1, L11, L21, L31, B11, USV11, USV31, USV26, USV46, USV66}. One of the states is the state 3 illustrated in Figure 13.

    S3 = belong(B11,R1), flapoutbase(UAV11, B11), start-monitor(UAV11, R1), discover(UAV11, Z11), discover(UAV11, Z22), discover(UAV11, Z63), undiscover(UAV11, Z32), undiscover(UAV11, Z42), undiscover(UAV11, Z53), supervise(UAV11, E11), supervise(UAV11, E31), adjacent(L11, L21), adjacent(L21, L11), adjacent(L21, L31), adjacent(L31, L21), occupied(L11), occupied (L21), occupied(L31).

Figure 13 UAV-M planning domain.
Figure 13

UAV-M planning domain.

  1. For the SUSV-C domain combined with USVS-C domain: an SUSV-C domain is illustrated with the USVS-C domain including a region (R1), three locations(L11, L21, L31), eleven cleaning vehicles (USVR34, USV22, USV52, USVR62, USV74, USV44, USV25, USV55, USV85, USV66, USV76), a crane (C11) and five dirty zones (Z12, Z42, Z63, Z22, Z53). The set of constant symbols is {R1, L11, L21, L31, USVR34, USV22, USV52, USVR62, USV74, USV44, USV25, USV55, USV85, USV66, USV76}. Figure 14 illustrates a state of this domain.

    S3 = belong(C11, L11), holding(C11, USVR34), end-clean(USV52, USV62, USV22, Z242), start-clean(USV74, USV44, Z42), start-clean(USV55, USV25, USV85, Z53), start-clean (USV66, USV67, Z63), at(USV22, USV52, USV62, L21), replace(USVR34, USVD44), replace(USVR34, USVD44), at(USV34, L11), adjacent(L11, L21), adjacent(L21, L11), adjacent(L21, L31), adjacent(L31, L21), occupied(L11), occupied(L21), occupied(L31).

Figure 14 SUSV-C planning domain combined with USVS-C planning domain.
Figure 14

SUSV-C planning domain combined with USVS-C planning domain.

5 Simulation

An illustrative example with two scenarios for dirty zones (with a homogeneous degree of dirt and a low degree of dirt) is provided to simulate the functioning of the proposed approach. Two trajectory planning solutions are given for swarm USVcz, namely the modified-GA and the modified-AA. The following measures allow us to highlight the contributions of the proposed approach: displacement energy consumption between the base of life and dirty zone, displacement-cleaning energy consumption in the dirty zone and total energy consumption of swarm USVcz.

5.1 Discretization of the virtual environment

Figure 15 illustrates a simplistic example of the virtual environment. The maritime space of a ‘Region’ is assumed to include a polluted ‘Zone’; a central unit consists of a base of life. Two different dirty zones are proposed according to the degrees of dirt in this region. After randomly defining the degrees of dirt in the environment with the two different zones, the discretization step is activated. Two matrices are obtained, where the black cells represent the dirty zone (Figure 16 and Figure 17).

Figure 15 Example of a simplistic virtual environment.
Figure 15

Example of a simplistic virtual environment.

Figure 16 Zone with a strong degree of dirt.
Figure 16

Zone with a strong degree of dirt.

Figure 17 Zone with an homogeneous degrees of dirt .
Figure 17

Zone with an homogeneous degrees of dirt .

5.2 Results

Two modified solutions for trajectory planning were used in this work. These solutions were implemented using a genetic algorithm and an ant algorithm. The two modified algorithms were programmed via open source Java. The simulations were run on a PC with a Core (TM) i5-5200U @ 2.20 GHz running the Windows 7 Professional operating system.

The proposed approach was implemented for a maritime region without hard obstacles that can prevent vehicles from navigating and plan their trajectories in this environment. This region includes a monitoring vehicle (UAVmr), a cleaning vehicle swarm (USVcz) and a dirty zone. Based on a metric map (Grid), the UAVmr captured data from its region. This data was measured against a color metric. These colors were partitioned on four intervals:] 0, 25],] 25, 50],] 50, 75],] 75, 100] involve a white cell (weak dirt), light brown (average dirt), dark brown ( medium-strong dirt) and black (strong dirt). The UAVmr classifies this data (degrees) of the cells by comparing the predefined threshold value (equal to 25% of the degree of dirt) with the Degreecell of each cell. The number of USVcz containing the swarm used in the simulations varied from 3 USVcz to 7 USVcz. Each USVcz swarm planned its movement based on optimal trajectories to reach its dirty zone and clean it. These trajectories were built based on a modified-GA or a modified-AA. The modified-GA was executed successively on each USVcz of the swarm.

The population was composed of five individuals and the maximum number of generations equaled to five because the solution obtained from the fourth generation was identical to that of the fifth generation compared to a tolerated threshold. The initial population was randomly generated where each individual (trajectory) had a start and end position. The tournament selection was applied to find the individual (trajectory) with a weak fitness (energy consumed). This fitness function used two balancing parameters: A = 0.02, B = 0.01. The crossover was used on this individual (the description cited in sub-section ‘Solution 1: modified-GA trajectory planning’). The mutation was not applied in this work because it was noticed that the two new children (trajectories) are 100% correct at the end of each generation.

In addition, the parameters of the modified-AA were used to find the best trajectory that will be applied to the swarm of USVcz are: τ0 = 0.1, ρ = 0.5, a = 2, b = 1, n = 90; number of time laps between t0 = 0 and tmax = 4. The cost value between the cells in the grid is randomly generated between 5 and 10. The energy required for the USVcz of the swarm to turn left / right from its position to another position is 0.2% and 0.05% be able to continue directly. When the USVcz swarm arrives at its zone, it starts cleaning dirty cells based on the proposed Algorithm 4. The proposed energy required to clean a black cell is 0.9%, for a medium-high dirt cell of 0.5% and for an average dirt cell of 0.2%. A formula was developed to calculate the total energy consumption (TEC) of each USVcz swarm: TEC = DEC1 + DCEC (DEC2 + CEC). This formula groups the displacement energy consumption of the base of life to the dirty zone (DEC1), the displacement energy consumption (DEC2) plus the cleaning energy consumption (CEC) in the dirty zone (DCEC).

5.2.1 Scenario 1: Zone with a strong degrees of dirt

This first scenario shows the simulation results of a dirty zone with strong degrees of dirt. These results give the curves of DEC1 (or DEC), DCEC and TEC of USVcz swarm for the two proposed solutions:

  1. Result of displacement Energy Consumption (DEC1): Figure 18 shows the results of the displacement energy consumption of each USVcz swarm from the base of life to its dirty zone. The modified-GA was compared with the modified-AA in terms of energy consumption (DEC1). It can be noted that the DEC curve of the modified-AA is less than the DEC curve of the modified-GA with a minimum gain of 1.01% and a maximum gain of 3.51%. Therefore, USVcz consumes less energy to plant its trajectory using the modified-AAalgorithm compared to the modified-GAwith an average gain of 2.62%.

  2. Result of displacement-cleaning energy consumption (DCEC): Figure 19 shows a simulation to evaluate the USVcz swarm behavior by its energy consumption for displacement and cleaning its dirty zone. Table 2 shows that the DCEC of the modified-AA decreases when the swarm is composed of 3, 4, 6 and 7 USVcz compared to the second DCEC with a low minimum gain of 0.5%. On the other hand, it increases rapidly when the swarm contains 5 USVcz with a maximum gain of 1.20%. Thus, the modified-GA is generally better than the modified-AA to move and clean with a USVcz swarm in a zone with strong degrees of dirt. Therefore, an average gain of 0.4% is obtained.

  3. Result of total energy consumption (TEC): the two previous results were combined to calculate the total energy consumption based on the two proposed algorithms. Figure 20 shows that the TEC curve of the modified-AA is below the TEC curve of the modified-GA with a minimum gain of 1.13% and a maximum gain of 3.5%. Therefore, the proposed modified-AA proposal consumes less energy than the modified GA with an average gain of 2.4% in a zone with a strong degrees of dirt.

Figure 18 Displacement – energy consumption in a zone with a strong degrees of dirt.
Figure 18

Displacement – energy consumption in a zone with a strong degrees of dirt.

Figure 19 Displacement – cleaning energy consumption in a zone with a strong degrees of dirt.
Figure 19

Displacement – cleaning energy consumption in a zone with a strong degrees of dirt.

Figure 20 Total energy consumption in a zone with a strong degrees of dirt.
Figure 20

Total energy consumption in a zone with a strong degrees of dirt.

5.2.2 Scenario 2: Zone with a low degree of dirt

The second scenario shows the simulation results for a zone with a low degrees of dirt. These results give the curves of DEC1 (or DEC), DCEC and TEC of USVcz swarm for the two proposed solutions.

  1. Result of displacement energy consumption (DEC1): Figure 21 shows the results of DEC1 of each USVcz swarm from the base of life to its dirty zone. The modified-GAwas compared with the modified-AAwith respect to DEC1. It can be noted that the DEC1 curve of the modified-AA is less than the DEC1 curve of the modified-GA with a minimum gain of 0.63% and a maximum gain of 3.4%. Therefore, the USVcz swarm consumes less energy to plan its trajectory using the modified AA algorithm compared to the modified-GA with an average gain of 1.71%.

  2. Result of displacement - cleaning energy consumption (DCEC): Figure 22 presents a simulation that evaluated the USVcz swarm behavior in DCEC in a zone with a low degree of dirt. Table 3 shows that the swarms of 3, 4, 5 and 7 USVcz consume almost the same displacement energy and clean-up by applying the modified-AA and modified-GA with a minimum gain of 0.01%. In addition, the amount of energy consumed by a swarm of 5 USVcz using the modified-AA increases rapidly with a maximum gain of 0.4% compared to the modified-GA. Thus, the modified-GA is generally better than the modified AA in moving and cleaning for the USVcz swarms in this dirty zone with an average gain of 0.4%.

Figure 21 Displacement energy consumption in a zone with a low degrees of dirt.
Figure 21

Displacement energy consumption in a zone with a low degrees of dirt.

Figure 22 Displacement – cleaning energy consumption in a zone with a low degrees of dirt.
Figure 22

Displacement – cleaning energy consumption in a zone with a low degrees of dirt.

Table 3

Displacement - cleaning energy consumption in a zone with a low degrees of dirt.

Numbers of USVczCEC_GACEC_AA
3266,95267,35
4285,2285,5
5322,8324,2
6329,05364,8
7380,25380,05
Average gain: 0.4%Minimum gain: 0.01%Maximum gain: 0.4%
  1. Result of total energy consumption (TEC): the two previous results were used to calculate TEC based on the two proposed algorithms. Figure 23 shows that the TEC curve of the modified-AA is below the TEC curve of the modified-GA with a minimum gain of 0.63% and a maximum gain of 3.4%. Therefore, the proposed modified-AA consumes less energy than the modified-GA with an average gain of 1.64% in a zone with a low degree of dirt.

Figure 23 DTotal energy consumption in a zone with a low degrees of dirt.
Figure 23

DTotal energy consumption in a zone with a low degrees of dirt.

5.2.3 Discussions

The USVcz swarm trajectory planning applied in this approach is based on two modifiable meta-heuristic methods: modified-AA and modified-GA. The implementation of these algorithms shows that the modified-GA takes a lot of computation time in the execution of its steps compared to the modified-AA. Thus, the convergence of its best solution reached a number of strong iterations compared to the modified-AA. In addition, a single path obtained / generated by the modified-AA is applied to a USVcz swarm in a sequential manner to arrive at its zone. However, the modified-GA generates a trajectory for each USVcz of a swarm while respecting the shape of a swarm. Therefore, the results of the simulation show that the USVcz swarm consumes less displacement and cleaning energy using the modified-AA compared to the modified-GA in zones with different degrees of dirt.

5.2.4 Positioning of the approach

This section positions the proposed approach in relation to the related works cited in Section 2. Each study mentioned has the characteristics / parameters that differentiate it from the others. Table 4 shows a comparison study of these studies and the advantage of the proposed approach. In this hybrid approach, a method of cooperation and coordination between a Generalcrd, a semi-autonomous UAVmr, and a USVcz swarm was proposed to accomplish the cleaning missions of dirty oceanic regions contrary to the work of [17]. In [17], the authors developed a complete frame-work for the design and control of swarms of autonomous collaborative robots, with particular emphasis on quad-copters collaborating with each other to perform space tasks.

Table 4

Comparison between several related works.

Work / Criteria[13][3][5][11][9][12][22][19][20][21][17]Proposed Approach
System typeCooperative orientation systemUSV Swarm path- following guidance systemUSV Optimal Planning System- complex obstaclesRobot exploratory path planning systemRobot exploratory path planning SystemMovement planning system- robot swarmsOn-Board real-time in-flight trajectory planner (RTTP)Prototype of a USVNew robotic system swarmUSV design systemOrganic computing approachMonitoring-cleaning system and USV swarms trajectory
Main objectiveMonitor/help human divers at sea-mission executionCombine swarm behavior-following guidance systemFind shortest optimal pathFind an optimal path between start/goal positionFind a path-goalPlan collision- free pathsVolcanic monitoring and ash sampling taskNavigation and localization the gas source of an oil spillOil Spill Cleaning UpOil Spill HandlingCollaboration of autonomous robot swarms to perform spatial tasksplanning Monitor ocean region UAV, clean-dirty zone and plan trajectory-USV swarm
Used type of methodPath- following cooperative, method- virtual targetSwarms aggregation, module-virtual targetIntelligent route planning-roulette, grid- obstaclesMax-Min ant System algorithmGenetic algorithm (GA)Potential-based GACollisionless trajectory planningResearch the road to get to the gas source (naviga- tion)Sensing, localization, navigation and collection an oil spillDetection and collection of samples in oil spillsDevelopment a framework for observer/ controller of this robot swarmsmodified-GA and modified-AA
Gear typeOne ASV, one R2 ROVAUVFour charlie USVOne USVPioneer P3AT RobotOne robot8 robotsOne Fixed wing UAV (4 Flights)One USVSwarm of ship robotsOne USVOne robot, two/four AR.Drone Parrot 2.0 quad-rotorOne UAV, Swarm USV
Environment3D marine complexesDisrupt- marineObstacle environmentPreviously unknownNot cited3D works- pacesVolcán de Fuego in GuatemalaSeaSeaSeaWorking area (simulation)Maritime-Atmosphere space
Algorithm / FunctionsFunction LyapunovFunction LyapunovAnt ColonyMMAS, A*, GAA*, GARepulsion-spring function, Voronoi and GARTTP based on GAGas sensors (concentration) and fuzzy logic controllerNavigation method and operation of the swarm, cleaning methodStraight- line tracking algorithm with GPS navigation, sampling mechanism and image- based detection algorithm (using automatic learning)Methods of O/C architecture modules, behavioural and swram control methodUSV numbers, M-AA, position adjustment, cleaning and situation 3
Selection typesNot citedNot citedNot citedNot citedTournamentHighest percentage (10%)RouletteNot citedNot citedNot citedNot citedTournament
FitnessNot citedNot citedNot citedTraveled- Euclidean distanceNot citedConfiguration formula (defined)Less dis- placement energyLow costNot citedNot citedNot citedNot cited
Metrics to measureHorizontal motion- speed of vehiclesRobots movements- speed, guidance -following pathOptimize path- obstacle environ- mentDistance traveled by antsDistance traveled by robotsBehavior of swarm trajectories in optimizing the configurationCost con- sumption of the road with and without obstacleUSV speed, gas sensing on the USV and error rate in the direction of the goalConsumption of money and time (in collecting small oil spills)Detection accuracy to classify samplesAdaptability of individual drone and optimization of the collaborationDEC, CECD and TEC of USVCZ swarm
SimulatorHIL[10]- ROS environmentKinematic- dynamic simulation- modelMATLABPlayer- Stage ToolsP-S ToolsPC (Core2 Duo 1.7 GHz CPUWXP)Hardware (Skywalker X8 airframe), Mission Control (MAVLink, ArduPilot, etc.), GCSUSV PrototypeRobot design (GPS module, communicatiodn System, monitoring program, etc)Robot Operating System (ROS), CORE2-ROS controllerRobot Operating System (ROS), Gazebo and Unity3D environmentPC (corei5-5200U-CPU2.20 GHzW7P)-java

Furthermore, the work in [13] proposed a trajectory planning guidance system based on a USVcz swarm. In addition, the article of [3] enhanced the first system for an ASVs, an AUV and a guide. The UAVmr of this approach locates and detects the dirty zone on the basis of its sensors like the developed USV [19], which enables the location of the gas source in the sea by two gas sensors. In [21], it extracts a sample of the surface water and runs an image-based detection algorithm to confirm the presence of oil. Depending on the data received and the map being explored by the UAVmr, the general coordinator can send a swarm of USVcz to each dirty zone by executing Algorithm 1.

Thus, in this paper two solutions were proposed for the trajectory planning from the base of life to the dirty zone for each USVcz swarm. The first solution is based on a modified-GA compared to the GA proposed in [24]. While the second modified solution is inspired by the ant algorithms proposed in [6, 25]. The swarm is moved in a square grid (space 2 D) discretized by UAVmr (Supmr). The cells are marked based on the degrees of dirt that the UAVmr processes according to the colors captured. On the other hand, the work of [5] used a grid that is modeled by black (obstacles) and white (clean) cells. In addition, a Voronoi free space scheme for modeling the work environment used in [12]. The swarm applies both solutions to find its trajectory with less distance. The fitness function of the modified-GA is calculated in relation to the energy consumed between the positions traveled and the energy consumed by all the actions performed (turn left / right or continue directly) by USVcz.

On the other hand, the fitness of [9, 12, 22] is based on the distance traveled and the Euclidean distance of the goal. The tournament selection method was applied in the modified AA while the roulette method was applied in [9, 11]. The USVcz swarm trajectory planning problem was managed to find its shortest trajectory. During simulation, it was noticed that the proposed algorithm MMAS [11] offers very good performances for the optimal path compared to a GA and an algorithm A*. Thus, the GA of [9] has a higher average performance than the one proposed by A* and C*. For this purpose, a dirty zone cleaning algorithm was applied to the USVcz swarm where each swarm can at the same time move and clean its dirty cells without specifying how to remove the dirt (the oil spill). On the other hand, the swarms of labor robots [20] can place the barge with oil suction equipment and move it to another location to remove the oil more safely.

The two proposed solutions were also compared with respect to the two different scenarios, namely a zone with a homogeneous degree of dirt and a zone with a strong degree of dirt. These scenarios were simulated according to three metrics: energy consumption of displacement of the base of life towards the dirty zone, energy consumption of displacement and cleaning in the dirty zone, and total energy consumption. The simulation results obtained confirmed the choice to use both solutions. Thus, the modified-AA algorithm gives encouraging results compared to the modified-GA algorithm.

6 Conclusion

This article has presented a hierarchical decision-making system for a hybrid air-sea approach. This approach uses a UAVmr for each maritime region and a USVcz swarm to clean dirty zones. In the monitoring step, the color was chosen as a degree of dirt for UAVmr to detect the dirty zones and the start of cleaning. During the cleaning phase, two solutions were proposed: ‘modified-GA’ and ‘modified-AA’. To this end, a USVcz swarm plans its displacement from the base of life towards its dirty zone. When this swarm arrives at its dirty zone, it begins to move and clean its dirty cells based on the proposed Algorithm 4. The USVcz swarm measures its amount of energy based on an energy threshold, and then sends its information to its Leadercz. The latter returns this information to its Supmr to find a USVcz competent. Supmr launches the USVcz(competent) which will replace the USVcz(discharge)when the energy amount of the latter becomes low. The proposition is formalized by means of a classical representation.

Two scenarios were proposed to simulate this proposal, namely a zone with a strong degree of dirt and a zone with a low degree of dirt. The measured metrics are the displacement energy consumption, the displacement energy consumption plus cleaning, and the total energy consumption for each USVcz swarm. The situation where the USVcz breaks down was not simulated in this work (a simulation was performed in [16, 23]). The simulation results show that the proposal applied with the modified-AA gives encouraging results compared to the modified-GA. This work did not address the problem of failure of the Generalcrd, Leadercz and the UAVmr in the execution of the tasks. Thus, the Leadercz was changed after the trajectory planning phase by one of its followers due to the lack of a powerful leader in terms of energy able to move, clean and receive / transmit data.

Therefore, as future work, the authors intend to develop a hybrid approach to address this problem. In addition, the authors aim to develop the modified-AA with a proposal of the wave propagation instead of pheromone, and to study the influence of speed variations of unmanned vehicles. Furthermore, the authors would intend to assign a cluster of drones for each region in a complex environment through solid obstacles, thus implementing an intelligent planning approach similar to the PSO method using fuzzy logic in combination with the bee colony algorithm.

References

[1] M. Kloetzer and C. Belta, “Temporal logic planning and control of robotic swarms by hierarchical abstractions,” in Proceedings of IEEE Transactions on Robotics (T-RO) vol. 23, no. 2, pp. 320–330, 2007.10.1109/TRO.2006.889492Search in Google Scholar

[2] M. M. Al-Rifaie and J. M. Bishop, “Stochastic diffusion search review,” Paladyn, J. Behav. Robot. vol. 4, no. 3, pp. 155–173, 2013.10.2478/pjbr-2013-0021Search in Google Scholar

[3] M. Bibuli, G. Bruzzone, M. Caccia, A. Gasparri, A. Priolo, and E. Zereik, “Speed constraints handling in USV swarm path-following frameworks,” in IFAC Proceedings Volumes vol. 46, no. 33, pp. 73–78, 2013, https://doi.org/10.3182/20130918-4-JP-3022.00031https://doi.org/10.3182/20130918-4-JP-3022.00031Search in Google Scholar

[4] S. Xiao-Wei, Study of mobile robot path planning [D] Shenyang: Northeastern University, China, 2008.Search in Google Scholar

[5] W. Yuan-Hui and C. Cen, “Research on optimal planning method of USV for complex obstacles,” in Proceedings of IEEE ICMA 2016 Harbin, 2016, pp. 2507–2511.10.1109/ICMA.2016.7558960Search in Google Scholar

[6] N. Labroche, N. Monmarché, and G. Venturini, “Visual cluster-ingwith artificial ants colonies,” in Proceedings of International Conference on KES-2003 Berlin, Heidelberg, 2003, pp. 332– 338.10.1007/978-3-540-45224-9_47Search in Google Scholar

[7] R. Kala, A. Shukla, and R. Tiwari, “Robot path planning using dynamic programmingwith accelerating nodes,” Paladyn, J. Behav. Robot. vol. 3, no. 1, pp. 23–34, 2012.10.2478/s13230-012-0013-4Search in Google Scholar

[8] D. Ferguson and A. Stentz, “The field D* algorithm for improved path planning and replanning in uniform and non-uniform cost environments”, Robotics Institute, Carnegie Mellon University, Pittsburgh: Tech. Rep, 2005.Search in Google Scholar

[9] V. de Carvalho Santos, C. F. M. Toledo, and F. S. Osório, “An exploratory path planning method based on genetic algorithm for autonomous mobile robots,” in Proceedings of 2015 IEEE CEC Sendai, Japan, 2015, pp. 62–69.10.1109/CEC.2015.7256875Search in Google Scholar

[10] L. Gao, S. Pan, and J. Shen, “A robot path planning scheme based on neural network,” J. Theor. App. Info. Techn. vol. 46, pp. 654–658, 2012.Search in Google Scholar

[11] V. D. C. Santos, F. S. Osório, C. F. Toledo, F. E. Otero, and C. G. Johnson, “Exploratory path planning using the max-min ant system algorithm,” in Proceedings of 2016 IEEE CEC Vancouver, BC, Canada, 2016, pp. 4229–4235.10.1109/CEC.2016.7744327Search in Google Scholar

[12] C. C. Lin, K. C. Chen, P. Y. Hsiao, and W. J. Chuang, “Motion planning of swarm robots using potential based genetic algorithm,” Int. J. Innov. Comput. I. vol. 9, pp. 305–318, 2013.Search in Google Scholar

[13] M. Bibuli, G. Bruzzone, M. Caccia, A. Ranieri, and E. Zereik, “Multi-vehicle cooperative path following guidance system for diver operation support,” IFAC-PapersOnLine vol. 48, no. 16, pp. 75–80, 2015.10.1016/j.ifacol.2015.10.261Search in Google Scholar

[14] M. Bibuli, M. Caccia, and L. Lapierre, “Virtual target based coordinated path-following for multi-vehicle systems,” IFAC Proceedings Volumes vol. 43, no. 20, pp. 336–341, 2010, https://doi.org/10.3182/20100915-3-DE-3008.00014https://doi.org/10.3182/20100915-3-DE-3008.00014Search in Google Scholar

[15] M. Bibuli, A. Gasparri, A. Priolo, G. Bruzzone, and M. Caccia, “Virtual target based path-following guidance system for cooperative USV swarms,” IFAC-Proceedings vol. 45, no. 27, pp. 362–367, 2012, https://doi.org/10.3182/20120919-3-IT-2046.00062https://doi.org/10.3182/20120919-3-IT-2046.00062Search in Google Scholar

[16] S. Bella, A. Belbachir, and G. Belalem, “A hybrid architecture for cooperative UAV and USV swarm vehicles,” in Proceedings of MLN’2018 Paris, France, 2018.10.1007/978-3-030-19945-6_25Search in Google Scholar

[17] S. Mammen, et al., “OCbotics: an organic computing approach to collaborative robotic swarms,” in Proceedings of IEEE SIS’14 Orlando, Florida, U.S.A., 2014, pp. 1–8.Search in Google Scholar

[18] A. Tahir, J. Böling, M.-H. Haghbayan, H. T. Toivonen, and J. Plosila, “Swarms of unmanned aerial vehicles – a survey,” J. Ind. Inf. Integration vol. 16, 100106, 2019.10.1016/j.jii.2019.100106Search in Google Scholar

[19] M. L. R. Putra, M. Rivai, and A. N. Irfansyah, “Unmanned surface vehicle navigation based on gas sensors and fuzzy logic control to localize gas source,” J. Phys. Conf. Ser., IOP Publishing IOP Publishing, vol. 1201, p. 012001, 2019.Search in Google Scholar

[20] E. M. H. Zahugi, M. M. Shanta, and T. V. Prasad, “Oil spill cleaning up using swarm of robots,” Advances in Computing and Information Technology Berlin, Heidelberg: Springer, 2013, pp. 215–224.10.1007/978-3-642-31600-5_22Search in Google Scholar

[21] W. Al Maawali, M. Al NaabiAl Yaruubi, A. Saleem, and A. Al Maashri, “Design and implementation of an unmanned surface vehicle for oil spill handling,” in Proceedings of IEEE 1st International Conference on UVS-Oman 2019Muscat, Oman, 2019, pp. 1–6.10.1109/UVS.2019.8658267Search in Google Scholar

[22] B. Schellenberg, T. Richardson, A. Richards, R. Clarke, and M. Watson, “On-board real-time trajectory planning for fixed wing unmanned aerial vehicles in extreme environments,” Sensors (Basel) vol. 19, no. 19, p. 4085, September 2019.10.3390/s19194085Search in Google Scholar PubMed PubMed Central

[23] S. Bella, A. Belbachir, and G. Belalem, “A centralized autonomous system of cooperation for uavs- monitoring and USVS-cleaning,” Int. J. Soft. Innov. vol. 6, no. 2, pp. 50–76, 2018.10.4018/978-1-5225-8365-3.ch015Search in Google Scholar

[24] M. A. Yakoubi and M. T Laskri, “The path planning of cleaner robot for coverage region using genetic algorithms,” Journal of Innovation in Digital Ecosystems(JIDES) vol. 3, no. 1, pp. 37–43, 2016, https://doi.org/10.1016/j.jides.2016.05.004https://doi.org/10.1016/j.jides.2016.05.004Search in Google Scholar

[25] C. Guéret, N. Monmarché, and M. Slimane, “Ants can play music,” in International Workshop on ANTS 2004 Berlin, Heidelberg, 2004, pp. 310–317.10.1007/978-3-540-28646-2_29Search in Google Scholar

[26] M. Ghallab, D. Nau, and P. Traverso, Automated Planning: Theory and Practice Edition Elsevier, 2004.10.1016/B978-155860856-6/50021-1Search in Google Scholar

[27] M. Ghallab, D. Nau, and P. Traverso, Automated Planning and Acting Cambridge University Press, 2016.10.1017/CBO9781139583923Search in Google Scholar

Received: 2019-10-07
Accepted: 2019-12-17
Published Online: 2020-04-29

© 2020 Salima Bella et al., published by De Gruyter

This work is licensed under the Creative Commons Attribution 4.0 International License.

Articles in the same Issue

  1. Regular Articles
  2. At first sight: robots’ subtle eye movement parameters affect human attentional engagement, spontaneous attunement and perceived human-likeness
  3. Smiling and use of first-name by a healthcare receptionist robot: Effects on user perceptions, attitudes, and behaviours
  4. A narrative approach to human-robot interaction prototyping for companion robots
  5. User-centered feedback design in person-following robots for older adults
  6. A hybrid air-sea cooperative approach combined with a swarm trajectory planning method
  7. The morality of abusing a robot
  8. Kaspar in the wild: Experiences from deploying a small humanoid robot in a nursery school for children with autism
  9. Special Issue on Love and Sex with Robots
  10. Some aspects of human consent to sex with robots1
  11. Sex care robots
  12. Learning to be human with sociable robots
  13. Falling in love with robots: a phenomenological study of experiencing technological alterities
  14. Making out with the world and valuing relationships with humans
  15. TouchYou: A wearable touch sensor and stimulator for using our own body as a remote sex interface
  16. How to apply Asimov’s first law to sex robots
  17. The moral case for sexbots
  18. Sex with robots: A not-so-niche market for disabled and older persons
  19. Moral psychology of sex robots: An experimental study − how pathogen disgust is associated with interhuman sex but not interandroid sex
  20. PLAY ME: interactive sonification of sexual arousal in long-distance relationships
  21. Love(rs) in the making: Moral subjectivity in the face of sexbots
  22. A revolution in sex education using sex robots
  23. “Intimate relationship” with “virtual humans” and the “socialification” of familyship
  24. Shared multisensory sexual arousal in virtual reality (VR) environments
  25. Sex robot technology and the Narrative Policy Framework (NPF): A relationship in the making?
  26. Should society accept sex robots?
  27. Topical Issue on Social Reception of Humanoid Robots
  28. The basic rules for coexistence: The possible applicability of metalaw for human-AGI relations
  29. Roboethics - Part I
  30. AI and recruiting software: Ethical and legal implications
  31. Topical Issue on Ethical, Legal and Societal Aspects of Wearable Robots
  32. Exoskeletons for all: The interplay between exoskeletons, inclusion, gender, and intersectionality
  33. Promoting inclusiveness in exoskeleton robotics: Addressing challenges for pediatric access
  34. Social Security and robotization: Possible ways to finance human reskilling and promote employment
  35. Responsible use of exoskeletons and exosuits: Ensuring domestic security in a European context
  36. Wearable robotic exoskeletons: A socio-philosophical perspective on Duchenne muscular dystrophy research
  37. ExosCE: A legal-based computational system for compliance with exoskeletons’ CE marking
Downloaded on 8.9.2025 from https://www.degruyterbrill.com/document/doi/10.1515/pjbr-2020-0006/html
Scroll to top button