Keywords

1 Introduction

Today there are several applications that need the use of articulated robots capable of moving in irregular areas in a given environment [1], so one of the main problems to solve by the branch of Robotics, is the development of path planning methods, that allow the movement of the quadruped robot to be autonomous [2].

The search for anti-collision methods has become one of the most fascinating topics in mobile robotics, and to achieve its goal, route planning algorithms and obstacle prevention algorithms are needed to avoid the obstacles that arise along the way [3]. The main problem of the planning of movement is to try to find a trajectory free of collisions, taking as reference a state of departure towards an objective state. During the last 15 years these techniques based on random sampling have had a particular interest. The RRT (Rapidly-exploring Random Tree) is based on the creation of branches of a tree in space, which iteratively samples new states and then directs the existing node that is closer to each sample to a new sample and thus forming a tree with ramifications [5].

For [4] the main purpose of road planning is to create algorithms that allow paths to be established considering restrictions in the movements of mobile robots. The Path Planning applications are oriented to different tasks that interact with the human being in different areas: (i) health: because it allows the support of robots in tasks for the elderly and people with paraplegia, (ii) military: because it is focused on the supervision of remote-controlled robots, autonomous and intelligent weapons, (iii) industrial: monitoring of robots with artificial intelligence through the use of mobile robots [5].

One key point to place the quadruped in space is being able to know its orientation to know where it needs to move, the determination of orientation of moving objects involved in numerous fields of science [6]. In order to get proper data to do the orientation estimate, there is necessary to process the raw signals received from the IMU, methods of signal processing are intensely researched to enhance the performance of the existing detection hardware [6, 7]. There are several methods to manipulate the data, in this article the Kalman filter was chosen to be implemented to obtain the estimation of the orientation of the Robot.

2 Related Works

The locomotion robots with legs can move with great ease in natural terrains, since they use discreet support points for each foot, in comparison with the robots with wheels, which require a continuous support surface. The main advantages of this type of robots are that they have great adaptability and maneuverability in terrains that are irregular [8]. Therefore, they are very good at moving on irregular terrains, thanks to two characteristics that they possess:

  • Vary the configuration of your legs to adapt to the irregularities of a surface.

  • The feet can make contact with the ground at the particular points according to the ground conditions.

For these reasons, the use of legs in robots is the best option for locomotion in irregular terrain. Although standing on four legs is relatively stable, the action of walking remains difficult because to remain stable, the center of gravity of the robot must move actively during the March.

One example of a quadruped robot developed at the Robotics Research Center, NTU, Singapore is LAVA [9]. The robot has two engines that are located in the hip section and the third is in the knee section. Each of the servomotors is coupled through a worm gear system to ensure a stable lock of the system that allows the engines to turn off when the vehicle with skid only needs to stop, which saves electrical energy

The human being can observe the world in three dimensions, each person can see different characteristics of their environment vividly with this three-dimensional perspective, so, with computer vision we try to simulate the vision that the human has by replacing the eye and the brain of the person with a camera and a processor. There are an infinity of applications in which you can use computer vision, one of them is the perceptual user interface where the computer is intended to have the capacity to detect and produce analogous signals from the human senses, such as allowing computers perceive sounds of their environment and produce a voice for it, also giving computers sense of touch and feedback force, and in this case, giving computers the ability to see, but these computer vision algorithms that claim to be part of a perceptual user interface must be fast and efficient [10].

There are different positions for the external camera, one of them is with a zenith perspective, that is, with the camera placed perpendicularly to the plane of the ground, to the plane of movement of the robot, this perspective was used by the work done by [11] in which the position of mobile robots and a ball in a game called robotsoccer was defined; Here, the color patterns were distinguished by the camera, but before that, the algorithm created first was a circle detection.

Finally, we turn our attention to the cognitive level of the robot. Cognition generally represents decision-making to achieve your objectives of higher order. Given a map and a target location, route planning involves identifying a path that will cause the robot to reach the target location when it is executed. Route planning is a strategic competence for problem solving since the robot must decide what to do in the long term to achieve its objectives [8], robots with RRT path planning are usually used in military applications because it is focused on the supervision [12,13,14] of remote-controlled robots, autonomous and intelligent weapons.

This work will control an autonomous robot, a tetrapod, using a camera with overhead perspective, which will use computer vision to navigate in chaotic environments, and to establish the orientation we will use an IMU in conjunction with a Kalman filter, that is, the angle in the plane of movement that the spider is in space. There are some methods for the recognition of the orientation, for example in [15] an online system was developed, due to the freezing of the gait (FOG), to detect falls and control tremors, a symptom present in the last stages of the disease of Parkinson. The system consists of a 3D camera sensor based on the Microsoft Kinect architecture, but for simplicity an IMU was used instead of this approach because it is a device that is effective, small and light because of this, it is used in several fields of science [6, 16].

3 Legged Robot

The physical design of the spider is somewhat simple, the mechanical part of SpiderRobot is composed of ABS plastic, the four legs of it are also made of this material. The axes and the form of movement of each joint are shown in Fig. 1.

Fig. 1.
figure 1

Motion axes of each leg.

In total, the robot has 12 motors, tree in each leg. The Robot’s control unit is based on an ATMega328 same one used on the Arduino Nano’s board. The PWM signals from the outputs of the ATMega328 board are transmitted over a connector board to servo motors. The block diagram of the system can be expressed as shown in Fig. 2. The camera sees the objects that surround the spider and where it is, and, with the help of the IMU its orientation, then the computer processes the RRT and finds a path that must be followed, calculates the direction that the robot must turn, and a command is transmitted over Bluetooth link to microcontroller. to the quadruped so that it is executed by the servos, and then the mechanism runs.

Fig. 2.
figure 2

Block diagram

The design of the robot in 3D can be seen on the left of Fig. 3 and on its right the robot printed and armed with all its electronic components.

Fig. 3.
figure 3

Spider robot

The mathematical analysis was made using the Denavit Hartenberg method, focused on one of the four legs of the robot, resulting in the following Eq. 1

$$ N = \left[ {\begin{array}{*{20}c} {\begin{array}{*{20}c} {\theta_{1} } & 0 & 3 \\ {\theta_{2} } & 0 & {5.4} \\ { - \pi /2 + \theta_{3} } & 0 & {7.8} \\ \end{array} } & {\begin{array}{*{20}c} {\pi /2} \\ 0 \\ 0 \\ \end{array} } \\ \end{array} } \right] $$
(1)

By using Matlab software, the leg motion and three joints is simulated by entering the values of the 3 angles, each angle modifying a joint, as shown in Fig. 4.

Fig. 4.
figure 4

(a) Leg simulation for: θ = 0, θ = 0, θ = 0. (b) Leg simulation for: θ = 0, θ1 = π/4, θ3 = −π/4

4 Mapping

In this project the following considerations were taken; For the computational development the OpenCV Software is used, available in the Python tool, the decision making is based on the information captured from the environment in which the robot is located through the camera as a visual sensor, from a top-down perspective to the plane, the IMU is used to estimate the position of the quadruped robot located inside the camera’s viewing area, for the evasion of obstacles, the properties of the static obstacles are known, which are identified using their morphology (rectangles).

4.1 Obstacle Avoidance Operation

The system has a camera connected directly to the computer by USB, image processing will be carried out on the Python platform that allows us to import artificial libraries, capture images from the screen in such a way that they remain in a range greater than 20 frames per second, enough to make the analysis of the obstacle evasion, according to the obtained data, Bluetooth commands will be sent to the robot to take the necessary measures (see Fig. 8).

4.2 Finding the Orientation of the Robot

To achieve a robust and reliable system in the determination of the orientation of the robot, artificial vision and inertial sensors that make up an Inertial Measurement Unit (IMU) have been used.

The IMU is a device used in several fields, since they are effective, small and light, the IMU used is the same as the work done in [16] developed at the Universitat Politècnica de Catalunya called 9 × 3 and has the objective of evaluating the symptoms of Parkinson disease (PD). The 9 × 3 Unit can be used 2 or 3 days working continuously and independently registers the signals of each of its sensors. The scheme shown in Fig. 5 shows the modules used for the execution of this investigation.

Fig. 5.
figure 5

9§3 general structure used with main connections.

The signals used for the orientation estimation are obtained only from the inertial sensors integrated in LSM9DS0 [17] which provides raw data and is composed of a 9-axis system composed of a magnetometer, a triaxial accelerometer and a triaxial gyroscope. These signals are sent in real time to the STM32F415RG microcontroller from STMicroelectronics, which processes and filters using a Kalman filter, obtaining as a result the estimation of the orientation which is subsequently sent to the PC to calculate the angle to be rotated. The quadruped robot with respect to the trajectory given by the RRT.

Additionally, In the robot we have two colors to locate the orientation of the robot spider red in the back and green front, from this, two points are obtained with coordinates, and next to a third point that indicates the route that the robot should follow Form a scalene triangle (Fig. 6).

Fig. 6.
figure 6

Scalene triangle, to determine the angle of rotation of the robot.

To find the angle of the robot with respect to the trajectory, we use the law of cosines and clearing the angle alpha obtaining Eq. 2 [17].

$$ \alpha = cos^{ - 1} \left( {\frac{{c^{2} + b^{2} - a^{2} }}{2 \cdot c \cdot b}} \right) $$
(2)

Because this formula only gives positive values of the angle, we also calculate the angle from the slopes of the lines that form it using Eq. 3.

$$ \alpha_{2} = { \tan }^{ - 1} \left( {\frac{{m - m^{{\prime }} }}{{1 + m \cdot m^{{\prime }} }}} \right) $$
(3)

An image of how the camera sees in overhead perspective can be observed in Fig. 7, in this you can notice an obstacle detected and the two colors placed on the spider.

Fig. 7.
figure 7

Quadruped robot and object

5 Rapidly-Exploring Random Trees

The RRT is one of the most suitable planners to solve several large route planning problems, since it shares many of the properties of the existing random planning techniques [18]. Below is the basic RRT expansion algorithm, taken from [18].

figure a

Figure 8 shows the flowchart of the trajectory tracking algorithm obtained from the RRT.

Fig. 8.
figure 8

Trajectory tracking algorithm flow diagram

6 Experimentation and Results

6.1 Optimal Delta for RRT

The objective of this experimentation is to get the fastest time to find the solution path with the RRT and have enough distance between each point that makes up the route, allowing the robot to move easily, because with many points, the robot would have to follow each one of them thus delaying the operation of moving from one point to another. For this, the delta constant of the RRT algorithm will vary between the following values: delta equal to 40, 30, 25, 20 and finally 10, the tests were performed in iterations of 10 times each and the average time was calculated.

In Fig. 9, we observe the results obtained for a Delta equal to 40 and the time in finding the route towards the objective, while decreasing the value of Delta as shown in Figs. 10 and 11, the time to find the route is considerably reduced, but as the Delta value continues to decrease, the mean time begins to elapse as shown in Figs. 12 and Fig. 13, so when increasing the time again it was seen that with a delta equal to 25 the best result was found.

Fig. 9.
figure 9

Test Delta = 40, average time to find the route equal 19.45 s.

Fig. 10.
figure 10

Test Delta = 30, average time to find the route equal 15.25 s.

Fig. 11.
figure 11

Test Delta = 25, average time to find the route equal 5.4 s.

Fig. 12.
figure 12

Test Delta = 20, average time to find the route equal 12.74 s.

Fig. 13.
figure 13

Test Delta = 10, average time to find the route equal 21.41 s.

Table 1 shows the results obtained by varying the variable to be able to determine the optimal Delta.

Table 1. Average time in each Delta value.

At the conclusion of the tests it was determined that the Delta equal to 25 is the most optimal to find the right path that the spider robot must follow, meeting the requirements of time and distance.

6.2 Mean Squared Error Between the Real and Ideal Route

We chose the Mean Squared Error to evaluate the error, since we obtain only positive values, facilitating the appreciation of the error.

The MSE of an estimator measures the average of squared errors i.e. the difference between the estimator and what is estimated. The difference occurs because of the randomness or because the estimator does not take into account the information that could produce a more accurate estimation 1.

With the MSE, we evaluated the quality of a set of predictions regarding their variation. As shown in Figs. 14 and 15 in which the route traced by the RRT and the ideal route are visualized.

Fig. 14.
figure 14

Real rute vs ideal, comparison between 2 routes to obtain the MSE.

Fig. 15.
figure 15

Real rute vs ideal, comparison between 2 routes to obtain the MSE., using Matlab software.

To obtain the average Quadratic Error, we use the Matlab software.

The results obtained from the MSE in the X and Y axes of each route are shown in Table 2. MSE of the real vs ideal route.

Table 2. MSE of the real vs ideal route.

7 Conclusions and Future Work

The method used in this work for the path planning is the RTT (rapidly exploring random tree) since it is able to determine relatively quickly the route that the quadruped robot must follow to reach its objective, allowing the autonomous movement of the robot in a certain area. With obstacles detected with morphological segmentation.

To estimate the orientation of the robot in the plane of movement, an IMU with the Kalman filter was used to combine the inertial data, and with the combination of 2 theorems the angle of rotation that the robot has to turn to follow the trajectory given by the RRT was used.

At the end of the performed tests to obtain the proper Delta value, we realized that the time it took to find the solution path increased with a relatively large or small Delta, therefore, we determined the optimal point of the value of Delta.

The optimum route is not the one that less distance traveled the robot but based on the obtained results it can be said that the best route to follow is the one that avoids the obstacles to a pertinent distance to not have collisions not planned by maneuver very close of the obstacle.

After carrying out the experimentation of the project, the level of illumination of the environment was established as a key point, since it is a determining factor for the optimal performance of the software, it was found that having a low level of lighting produces difficulties when recognizing colors and objects.

As a future work, other algorithms for path planning such as PRM, A*could be tested and implemented to see if they work better that the RRT described in this paper [19], and an object detection module with a path planner and deep learning methods.