Introduction

An extensive study has been conducted on autonomous service-based robot navigation in indoor environments. The indoor-based service robots are differentiated as per environment such as industry, home applications, hospital and cafeteria/hotel. In COVID-19 pandemic, the importance of service robot has been recognized for social services. The warehouses and industries are also integrated with robots for carrying the products.

The challenges of individual robots at the warehouse are carrying products with outbound due to bigger sizes than the basement of the robot, where it creates a chance for collision and cross docking at the environment. In this regard, individual robots can carry products when the product size is less than the robot basement size. Cranes can be used for carrying huge products, but they cannot be opted for the medium sized products due to space issues. It is one of the major challenges in warehouses and industrial environment. This paper provides solutions using cooperative-type multi-robot for carrying medium-sized products. In this context, the collaboration of multi-robot with the cooperative-type formation plays a vital role. This cooperative mechanism impacts the multi-robot to traverse with the behavioral control among them to defined destination nodes.

The research towards shortest path planning has been protracted in the robotic field from few decades, which is essential to accomplish the robotic navigation. Most of the navigational algorithms have been developed based on grid map and graph theory. The Dijkstra algorithm is one of the familiar shortest path planning algorithms, and it is widely used for 2D mobile robot navigation. Edsger Wybe Dijkstra is a Dutch scientist, expert in the computer field; he proposed shortest path planning as a Dijkstra’s algorithm. In the recent years, the algorithm is modified with various aspects as per real-time scenario; the authors K. Wei et al. [1] represented about how a maximum load path problem can be dissolved with modified Dijkstra’s algorithm. Similarly, the same algorithm has been used for optimal path and other applications like parking of robots [2].

The authors Dong Guo et al. [3] has mentioned about emissions effect while driving and also about fuel consumption by using the shortest path method. The automatic guided vehicle transmission in an environment with the grid method using Dijkstra algorithm was represented by Zheng Zhang et al. [4]. The team of authors Deepak Gautam et al. [5] discussed regarding Dijkstra-based shortest path for quad rotor helicopter movement. Sai Shao et al. [6] mentioned about the importance of shortest path in light-sport aircraft transmit. The authors M. Luo et al. [7, 8] have discussed regarding the extended version of the Dijkstra algorithm for optimal path planning. Thus, path planning is highly indeed in an industrial environment for material transportation.

In the existing system, at warehouse and industries the products are carried out by individual autonomous robot and they are not capable of carrying the medium-sized products. In this aspect, the multi-robot-based transportation methods are essential to carry medium-sized products using collaboration methods.

The collaboration of motion robots like PUMA 560 arms for carrying payload was presented by H. Bai et.al [9]. In similar lines, bio-inspired methods like coalition formation of multi-robot to execute gaming theory of robotics is mentioned by authors X. Liang et al. [10]. One of the robot formations with queue structure was developed by authors C. Fua et al. [11]. The authors Y. Kim et al. [12] investigated about formation of multi-robot with localization strategy.

The behavioral control between robots is another aspect of multi-robot formation. The cooperative control methods for vehicle formation have been developed by W.Ren et al. [13]. The other researchers G. Antonelli et al. [14] mentioned about control algorithms of null-space-based behavioral (NSB). The researchers have contributed control mechanism with fuzzy methods by authors J. Huang et al. [15], and multi-robot control with adaptive methods was discussed by J. Fan et al. [16]. The leader follower approaches are one of the best methods in the cooperative formation of multi-robot. The leader follower method for mobile vehicle was described by Shao et al. [17]. V. Kumar et al. [18] have mentioned regarding obstacle avoidance using Gaussian algorithms with a heuristic approach for leader follower formation control.

The obstacle avoidance can be performed by a multi-robot with two approaches: 1. distributive formation behavior control and 2. centralization formation behavior control. Among these, centralized approach is an appropriate method used in the flock group for transportation of products. The single-robot obstacle avoidance is mentioned with various control methods such as bug, vbug, bug2, voronoi diagram and graph theory. The key aspect of centralized multi-robot approach is leadership, and it plays a vital role in the execution of the multi-robot transportation with obstacle avoidance.

In this context, at dynamic situations, leadership swapping between multi-robot is essential. The affection-based concept between robots has been represented by F. Li et al. [19]. The practical leader–follower concept with the tracking control of multi-robots has mentioned by Y. Wang et al. [20]. The obstacle avoidance between multi-robot has been specified by X. Wu et al. [21]. The vision-based methodologies have arbitrated into robotics object avoidance by Y. Wang et al. [22] to evaluate the shape and size of the object in the process of obstacle avoidance execution. The authors D. Sakai et al. [23] have represented about the obstacle avoidance with preserving connectivity and without data transmission.

To accomplish the real-time robotic algorithms like navigation, obstacle avoidance and behavioral control is depended on computational devices and sensory data acquisition. The processing of these robotic control algorithms is required for parallel computing devices such as CPU/laptops. In this perspective, power consumption is another challenge while executing mobile robot; it impacts power management of battery mentioned by Yongguo Mei [24]. Field-programmable gate array (FPGA) will provide optimized power consumption with high computation which are appropriate for mobile robot. In this view, few researchers have deployed their respective navigation and obstacle avoidance algorithms on FPGA devices [25,26,27,28].

The proposed research work consists of novel hardware schemes for integration of multi-robot navigation using an extended version of the Dijkstra shortest path planning along with the bug2-based obstacle avoidance with the Delaunay triangulation approach. The other novelty of research work is formation of mechanism with behavioral control between multi-robot at both navigation and obstacle avoidance scenario. The static and dynamic leadership as part of leader and follower approaches is one of the novel approaches with hardware schemes. These three novel modelings are integrated into a single unit to perform parallel processing. The proposed VLSI architectures are versatile with parallel processing which is a novel approach.

This paper contribution is organized as follows: the proposed transportation based on multi-robot, shortest path navigation with static and dynamic obstacle avoidance and also along with behavioral control between multi-robot is discussed in section II. The VLSI architectures for proposed multi-robot services at warehouses and industrial applications are discussed in section III. In section IV the proposed work is illustrated with simulation results and synthesis results of the multi-robot navigation, behavioral control and leadership swapping methods. Section V deals with the conclusion and future research works of the paper.

Autonomous-based Multi-robots for Intelligent Transportation

The autonomous-based multi-robot systems are used for intelligent transportation in indoor environment such as warehouse and industrial environment. The extended version of the traditional Dijkstra algorithm is used for navigation of the multi-robot. The behavioral control approaches between the multi-robot have been developed with affection-based method, and obstacle avoidance is performed with integration of bug2 algorithm and Delaunay triangulation method.

The autonomous multi-robot system (MRS) with formation is represented in Fig. 1. The small MRS flock group is considered with four robots, each edge of the product is carried out by one of the MRS team. And MRS team will maintain equidistance with other teammates. The position of MRS team is represented by the robotic names as R1….R4, and it is represented in matrix formation as follows.

Fig. 1
figure 1

Illustration of multi-robot formation with equidistance

Pseudo-Code of Hardware-Based Shortest Path Planning of MRS

The extended version of the Dijkstra algorithm for shortest path planning is framed using nodes (N) and route weights (W) as digraph D = (N, W). The distance between two nodes is calculated using the Euclidean distance method. Graphically represented in Fig. 2, the essence of the algorithm is to find shortest path when the initialization node and the destination node are given. Let us consider the MRS team starts from node ‘A’ to targeted node ‘I’. The number of paths is available with different route weights; among them, the shortest route is A-D-F-I as per route weights as 30. The extended version is Dijkstra with Delaunay triangulation for MRS.

Fig. 2
figure 2

Illustration of Dijkstra algorithm with route map

Inputs: The MRS team navigation is sensitized with ultrasonic sensors to traverse in the environment. This sensor array is placed on robot as follows: S_x = {SF_x, SL_x, SR_x, SB_x}, and digital compass is essential to calculate the angular deviation of mobile robot at node points, and it is noted as DC_R_x.

Step 1: Localization and destination nodes are initialized with explicit communication to MRS team’s G_L. As the Dijkstra algorithm has the information on all possible paths and distances for various routes, among all the paths the shortest path is confined as per the inputs.

Step 2: Let us consider the navigation as mentioned, example: ‘A’ as a start node and ‘I’ as a destination node, shortest route: A-D-F-I. The MRS team will be registered with the shortest route, while MRS G_L will initiate their navigation with behavioral control mechanism.

Step 3: MRS team’s G_L with S_x sensory information, E_D is initialized with route weights as E_D1 for A to D nodes, D_En = 0, I_N = A and D_N = I, EDT \(= \sum ED1. \ldots .EDn\).

If (S_x = {0, x, x, x}) && BC_MRS = 1.

If (D_En ≠ E_D1) && (R_w ≠ EDT).

{

G_L (ML = 1, MR = 1).

}

Else if (R_w ≠ EDT).

{

G_L (ML = 0, MR = 0).

E_D = E_Dx+1 (it means route weight from D to F).

}

Else

{

G_L (ML = 0, MR = 0).

P_N = D_N, MRS reached the destination node.

}

End

Else if (S_x = {1, x, x, x}) && BC_MRS = 0.

{wait until BC_MRS = 1}.

Else if (S_x = {1, x, x, x}) && BC_MRS = 1.

{

MRS team executes the obstacle avoidance algorithm.

Then retrieve back to navigation algorithm.

}

Else

{

G_L (ML = 0, MR = 0).

P_N = D_N, MRS team reaches the destination node

and waits for next instructions.

}

The above pseudo-code represents the shortest path planning with behavioral control. In the example, initial and destination nodes are ‘A’ and ‘I’, respectively. When the front sensor of MRS team’s G_L = 0 (leader) which indicates no obstacle, then after immediately, it checks for BC_MRS = 1, where data from BC_MRS give the presence of follower robot. MRS G_L moves forward until it completes route weights (R_w) by checking the distance from node to node (‘A’ to ‘D’, ‘D’ to ‘F’ and ‘F’ to ‘I’). The MRS team executes the obstacle avoidance followed by the navigation, if the front sensor of G_L = 1. G_L always checks for BC_MRS = 1 to maintain the synchronization among them.

Remark: In the navigation, MRS team will change global leader, according to the dynamic conditions, and navigation is continued from the same place.

Pseudo-Code of Hardware-based Behavioral Control of MRS

The behavioral control between MRS team formation is constructed with kinematic momentums as 1. initial stage, 2. locomotion stage and 3. terminus stage.

Figure 3 illustrates the MRS team’s behavioral control mechanism. Among MRS team, global leader will be decided with respect to flock group direction movement. Towards the north direction, R3 is considered as a leader. In similar lines for east, south and west directions, the R4, R2 and R1 will act as global leaders respectively.

Fig. 3
figure 3

Behavioral control between MRS

At the initial stage, the G_L robot takes the first movement as illustrated in Fig. 3b, the next step will be performed by I_L, and then R1 will be the leader as presented in Fig. 3c. The R2 and R4 react to the actions of the G_L and I_L.

The locomotion stage will be executed after the initial stage and robot’s synchronization momentum as illustrated in Fig. 3a. In terminus stage G_L, I_L and F_F sequentially stops the navigation and maintain the equidistance.

Inputs: S_x = {SF_x, SL_x, SR_x, SB_x}, IR_x = {IR_R_x, IR_B_x, IR_L_x, IR_F_x} and digital compass on robot x (DC_R_x).

Step 1: Initialization: DC_R_x = \({0}^{0}\), represents robots are facing towards north direction. In such conditions R3 acts as G_L, R1 as I_L and R2 & R4 as F_F. Initial robot's status is represented as shown in Fig. 1.

Step 2: If ((DC_R_GL = \({0}^{0}\)).

If (SF_3 = 0),

{

R3 robot takes the movement with the velocity of y units

} Perform step 3.

Else (SF_4 = 0) && (SL_4 @ ϑ450 = 1)

{

R3 is blocked with obstacle due to this, leadership swaps to R4, it acts as G_L, R3 as I_L, R4 takes ϑ450 right movement, followed by R3, R1 and R2 as mentioned in Fig. 3. R4 operated with a velocity of y units.

},

Else If ((DC_R_x = \({90}^{0}\)),

\(\therefore\) Leadership swap to R4.

Similarly, R4 acts as GL, R3 as I_L, R2 & R1 act as F_F as represented in Fig. 4b

Fig. 4
figure 4

Static position of robots as per indoor environment

Else If ((DC_R_x = \({180}^{0}\)),

\(\therefore\) Leadership swap to R2.

Similarly, R2 acts as GL, R4 I_L, R3 & R1 act as F_F as represented in Fig. 4d

Else ((DC_R_x = \({270}^{0}\)),

\(\therefore\) Leadership swap to R1.

Similarly, R1 acts as GL, R2 as I_L, R3 & R4 act as F_F as represented in Fig. 4c.

Step 3: The G_L robot moves with \(y\) velocity by maintaining the distance as illustrated in Fig. 3, \(\therefore\) I_L robot acts as the follower moves with \((y+Rs)\) times velocity. The F_F moves with \(2y\) times velocity. This velocity is preferred until each robot reaches DR_R distance values. Next fetch to step 4.

Step 4: Once initial speed synchronization completes with step 3, robots will move with equal \(y\) units velocity and maintain the DR_R distance.

The above pseudo-code represents the behavioral control among multi-robot and swapping of leadership in dynamic scenarios. The speed velocity of individual robot differs from each other in order to maintain the synchronization. Initially in Fig. 4a, robot R3 acts G_L as it is free from obstacles and it continues its leadership mechanism until it gets obstructed by all surroundings. In Fig. 4b, robot R4 acts as a global leader as all the other robots are surrounded by obstacles. Similarly, in Fig. 4c–d the leadership is owned by robot R2 and robot R1 respectively.

Pseudo-Code for Hardware-based Behavioral Control of MRS Obstacle Avoidance

Inputs: S_x = {SF_x, SL_x, SR_x, SB_x} & DSF_x = {DSF_x, DSL_x, DSR_x, DSB _x} and digital compass on robot x (DC_R_x).

Step 1: If ((DC_R_x = \({0}^{0}\)).

If (SF_3 = 1) && If (SF_4 = 1)

{R3 & R4 robots detect an obstacle} as illustrated in Fig. 5a

Fig. 5
figure 5

a-d MRS obstacle avoidance with behavioral control. eh MRS obstacle avoidance with behavioral control

Go to step 2 Else {R3 & R4 Robots will move forward}.

Step 2: If (SF_3 @ ϑ450 = 0, SF_4 @ ϑ450 = 0),

R3 & R4 will take ϑ45 rotation towards the right, illustrated in Fig. 5b.

R1 & R2 will delay until R3 &R4 accomplishment of the job.

Go to step 3.

Else (SF_3 @ ϑ3150=0, SF_4 @ ϑ3150=0)

R3 & R4 will take ϑ45 rotation toward left,

R1 & R2 will delay until R3 & R4 accomplishment of tasks.

Go to step 4.

Step 3: R3 & R4, R1 & R2 are rotated toward ϑ450. Move forward with the same angle as illustrated in Fig. 5c.

The leader robot will calculate the distance with internal odometer methodology.

  1. a.

    The robots take rotation with ϑ45 towards the left. R3& R4 and R1 & R2 move forward until the next edge as illustrated in Fig. 5d.

  2. b.

    The leader robots will take ϑ45 towards the left and followers will wait until leaders complete their action as illustrated in Fig. 5e.

  3. c.

    The follower robots will rotate to ϑ45 left turn. The leaders and follower will move forward until decrement of odometer values as shown in Fig. 5f.

  4. d.

    The leaders will rotate to right ϑ45 and follower in Fig. 5g.

The follower also completes the similar task as leaders as shown in Fig. 5h.

Step 4: Similar to step 3 movements, the robots will move, act as anti-direction of the step 3.

The above pseudo-code describes obstacle avoidance of MRS by maintaining behavioral control. The leader robots move forward by sensing the obstacle and waits for the delay time until it gets synchronized with follower robots. The odometer values are stored by the robots in order to retrieve the line of the path.

VLSI Architectures of Multi-Robot System for Intelligent Transportation

The MRS team is deployed with VLSI architecture for an intelligent transportation, which plays a vital role to accomplish successful transportation in industrial environment. The overall VLSI architecture of the MRS team for intelligent transportation is illustrated in Fig. 6; it consists of sensor module, control unit, navigation module, behavioral control module, obstacle avoidance module, processing and execution modules.

Fig. 6
figure 6

Overall hardware scheme for MRS intelligent transportation

The input sensor module resided with infrared sensors (IR_1…IR_4), ultrasonic sensor module (US_1…US_4) with a pulse width distance converter and digital compass to evaluate the robot direction. The robots are integrated with infrared sensors on each side of bottom corner of the robots, it is placed to evaluate the beside robot movement. The ultrasonic sensors are placed in the middle of each side on the top of the robot. Digital compass is placed on the front side of the robot. The execution module is interfaced with stepper motors and wheels (ML, MR).

Control Unit of Robot for Intelligent Transportation

The control unit (CU) is the heart of the system, and the sensors are interfaced to CU by using protocols like UART. The digital compass has interfaced with UART protocol. Ultrasonic sensors are triggered and received its echo signal in the format of distance using PWDC. The output of PWDC is applied to navigation, obstacle avoidance and behavioral control module. The sensors have different frequencies such as ultrasonic sensor operates at 40 KHz and stepper motors operates at 10 KHz. An FPGA device (Xilinx Zynq-7000 SoC ZC702) is used as CU and it operates at 100 MHz frequency.

All these frequencies are synchronized by CU and operated in parallel. The CU takes care of the system until it executes unit. As part of synchronization, the data driven from the various modules are different in size and it is synchronized with appropriate action as per the condition.

The processing module (PM) is under control of CU, as per algorithm. The PM consists of processing elements (PEs), and each PE is interfaced with other modules such as navigation module, obstacle avoidance module and behavioral control module. PE of the navigation module in PMs will process the conditions of shortest path planning and it drives the execution module (EM). EM is interfaced with motors such as stepper and servo motors. The servo motors are placed on top of the robot and ultrasonic sensors are placed on servo motor; for example, servo motor is used by F_F robot to estimate the G_L robot movement as part of behavioral control. The stepper motors are used to drive the robot, and it is integrated with driver circuits and wheels. Total MRS team is coded in Verilog HDL and synthesized by using the Vivado 17.1 software.

Navigation Module of MRS

The VLSI architecture for shortest path navigation used MRS team for intelligent transport. The CU enables the navigation module; it sensitizes the sensory information of ultrasonic sensor and compass to localize the node. It receives the destination node as a task to all the robots with explicit communication. The navigation VLSI architecture is illustrated in Fig. 7, and this architecture is deployed in all robots. The G_L robot takes lead as a leader as per the robot's direction.

Fig. 7
figure 7

VLSI architecture of MRS navigation module

The shortest path module is an internal part of the architecture. In the known environment, learning is conducted earlier before the validation of navigation. In the learning process all different probabilities of short path as per Dijkstra and Delaunay triangulation are designed and registered in the look-up tables (LUT) of the FPGA. The sample inputs are as follows: initial localization of the robot at node 'A' and destination node are applied as ' I '. The shortest path module routes reference values as compared with applied inputs. If both comparators output with high '1', we get results to select the shortest path, i.e., LUT slice. This path is stored in the route map module (Table 1).

Table 1 The notations used in this paper

The route map splits the route into smaller destinations and applies same to Euclidean distance. As per example, the shortest path is registered as A-D-F-I, A-D route is weighted as 10 units of the environment, and these distance values are mapped in the Euclidean distance module. The soft digital encoder is designed, and it calculates the distance of the robot traversal in the environment. The navigation control unit operates on two levels as synchronizing the total navigation module and another level as comparing between the Euclidean distance of the shortest path destinations and robot real-time distance registered at soft encoder. At the same time, navigation module will communicate in parallel with the behavioral module, processing module and obstacle avoidance. The computational challenges are at obstacle avoidance conditions. The distance error is calculated by navigation control unit and redefining with the Delaunay triangulation method.

Behavioral Control Module of MRS

The behavioral control module (BCM) consists of four internal modules such as leader module, follower module, swapping module and behavioral control unit. The BCM is enabled with the MRS team control unit, and BCM is sensitized with PWDC, digital compass UART output and interfaced with CU, navigation module, obstacle avoidance and feeding the response to the processing module. The behavioral control unit maintains the BCM and instructs the MRS team as per the algorithm.

The leader module is activated as per the behavioral control algorithm; G_L robot plays a behavioral role taking care of the environment conditions and follower robot movements. The novelty of the behavioral control has designed without data transmission. IR sensor of the robot estimates movement of the robot and ultrasonic sensors information is estimated for the follower distance from its point in dynamic conditions using Euclidean distance approach and velocity.

The follower module classifies with multiplexers; either it is in I_L or F_F mode. The I_L and F_F strategies are different in movements and distance conditions. Movement of MRS team formation shapes is changed from square to rhombus. After achieving synchronization of all robot movements, it enters into locomotion movements. In locomotion condition, G_L, I_L and F_F maintain equal distance using ultrasonic sensors and IR sensors.

The swap module is used to switch robot either in leader or follower mode. It is differentiated as per the direction and obstacle avoidance at deadlock situations.

Obstacle Avoidance of MRS

The MRS of an obstacle avoidance is enabled as per the conditions from both navigation module and BCM. The obstacle avoidance is designed based on the bug2 (illustrated in Fig. 5a–h) and Delaunay triangulation methods.

PWDC is used for evaluating the type of object; either it is static or dynamic. In dynamic conditions, the velocity of the object is evaluated using a Euclidean distance method with the support of PWDC hardware module. The BCM is used at the time of bug2 algorithm execution. The triangulation with Euclidean distance is used to compute the size of the object and to perform as shown in Fig. 5g, h.

Results

MRS Synthesis report

Table 2 is about the device utilization of behavioral control of MRS team obstacle avoidance. As mentioned in Fig. 4, the hardware schemes of obstacle avoidance of MRS team are coded in Verilog HDL and synthesized by using the Xilinx Vivado 17.1 software. The area occupied by each submodule of the algorithm is stated as the number of look-up tables (LUT) occupied in the Zynq board. All the submodules of the algorithm used 14,992 slices of LUT. Overall device utilization is about 28.18% which is achieved with the proposed work using Zynq-7000 SoC ZC702-type FPGA. The static power consumed by the proposed research work is 6.2 watts, as per Xilinx power analysis.

TABLE 2 Device utilization of MRS

Simulation Results

Figure 8 represents the control unit actions of overall simulation results. It represents the robot movements, and it checks the status of all control signals. It is representing the leadership of robot and swapping toward as per robot conditions as shown in Fig. 3a. The timing analysis is decreased to achieve the results in simulation.

Fig. 8
figure 8

Simulation results of overall control unit module

Figure 9 represents about the obstacle avoidance of the R3 robot. The SF, SB and SL are facing obstacles, before SR no obstacle as mentioned in Fig. 3b that robot takes action to the right turn. The temp1, temp2 and temp3 register is used to store the data of distance traveled by the robot in overcoming the obstacle. These position changes are mentioned at POS [2:0].

Fig. 9
figure 9

Simulation results of obstacle avoidance of robot R3

In Fig. 10, simulation shows the bug2 obstacle avoidance algorithm from initial point to destination for the robot R4. The R4 moves with different velocities of speed to maintain the synchronization with R2 with respect to the digital compass input and sensory information. The variations of directions and its self-localization are shown in Fig. 10.

Fig. 10
figure 10

Simulation results of R4 from the initial point to destination point

In Fig. 11, simulations show the behavior of synchronization between robot R4 and robot R2. The front sensor data are continuously checked by R2 to get the information about the presence of R4. The motor signals are shown in the simulation.

Fig. 11
figure 11

Simulation results of R2 with synchronization of R4

In the Fig. 12, the task is given to the robot as the initial node as A = 4’b0001 and destination node as I = 4’b1001. For a given task, mode is switched to 4b0001 where all the possible paths from ‘A’ to all destination nodes are available, and for a given input, shortest path is A_D_F_I. The robot navigates through A = 4’b0001, D = 4’b0100, F = 4’b0110 and I = 4’b1001 indicating the register node_reg. Respective motor signals are executed through xl_next, dl_next, xr_next and xr_next.

Comparison

The proposed research work is integrated with multi-robot navigation, behavioral control and obstacle avoidance by multi-robot methods. K. Wei et al. [1] have discussed an extended version of Dijkstra algorithm, but it is represented for individual robot. F. Li et al. [19] have presented about affection-based leader selection method among MRS. The proposed work is on similar lines of the Dijkstra algorithm for multi-robot system (MRS) navigation along with behavioral control which is one of the successful accomplishments and MRS performing static obstacle avoidance with the flock group is another achievement. P. R. Kumar et al. [29] have presented hardware schemes for a single robot. The proposed hardware schemes are developed with optimized coding techniques; with this it consumes less look-up tables and slices of FPGA around 28% of Zynq Zed board FPGA device. The power consumed for robot navigation of 40 nodes (and 52 edges) is 6.2 watts, and it is analyzed by the Xilinx Power Estimator (XPS) tool (Fig. 12).

Fig. 12
figure 12

Shortest path navigation

Conclusion

The proposed research work has been developed for intelligent transportation by autonomous multi-robot system (MRS). The novel contributions of research work deployed for intelligent transportation are shortest path planning of robotic navigation using Dijkstra algorithm, BCM with leadership swapping method and obstacle avoidance in real-time scenario. The VLSI architecture has been developed for successful accomplishment of algorithms. The state of the art is the integration of three algorithms, robot navigation, and its equivalence hardware scheme has been developed. The behavioral control played a vital role in communicating MRS team without data transmission which is one of the novel approaches. This method decreases the chip area of the FPGA. Another novel approach is accomplished of obstacle avoidance in lines of bug2 for intelligent transportation in real time with BCM. This hardware scheme is simulated and synthesized using the Xilinx Vivado 17.1 software. The device utilization represents the hardware schemes occupancy of the look-up table (LUT). The 28.18% of LUT are used as part of Zynq-7000 SoC ZC702-type FPGA. As per the Xilinx power analysis, it consumed 6.2 watts of static power for proposed research work.