Keywords

1 Introduction

A two-wheeled legged mobile robot is a naturally unstable system with high order, nonlinearity, strong coupling, underactuated, etc., and the design of the balance controller is a difficult task, and most of the existing works use the model-based Linear Quadratic Regulator (LQR) technique to solve the balance problem, whose performance is highly dependent on the accuracy of the technique regarding the dynamic model. Scholars at home and abroad have made relevant research in the balance control of wheel-legged robots, and Sanyo Electric Company [1] proposed a way to indirectly change the overall center of gravity of the robot through the forward and backward probing of the head, so as to achieve the purpose of controlling the robot's forward and backward movement. Tencent Robotics Robotics X [2] used the output regulation of a linear system to estimate the error between the actual forward tilt angle of the robot and the forward tilt angle in the inverted pendulum model so that the robot can maintain balance. Wang xiaoyu [3] et al. established a complete dynamics model, and an adaptive control algorithm was applied to the controller in order to improve the anti-interference ability in the balanced state. Harbin Institute of Technology [4] has designed a gain adjustment controller based on self balancing, consisting of a real-time centroid calculator and a feedback controller based on centroid adjustment.

Due to the complex mechanical structure of wheel-legged robots, it is difficult to establish an accurate dynamic model for wheel-legged robots. In addition, when the physical parameters of the robot change, the model-based controller parameters need to be manually adjusted again to ensure system stability, which affects the automation of the robot. In contrast, with the adaptive fuzzy PID control system, the robot height and tilt angle will be adjusted in time when they change to keep the car body stable, which can solve the problem of balance and stability of the wheel-legged robot [5]. At the same time, due to the changes in the attitude of the two sides of the wheel-legs and the speed and steering of the body need to be accurately controlled by using the traditional PID. Therefore, a control system based on the fusion control of adaptive fuzzy PID and traditional PID is designed to improve the balance stability of the wheel-legged robot.

2 Structural Design

In order to meet the needs of intelligent logistics, the logistics and distribution mobile robot is designed into the structure shown in Fig. 1. It consists of a seven-link mechanism to form a unilateral wheel leg, two sets of three-link symmetrically distributed, and the angle is adjusted by the leg drive rods \(l_{AB}\) and \(l_{HG}\) to keep the body smooth, while the legs are added at the bottom end to improve the stability and robustness of the operation of the mobile robot.

Fig. 1
2 photographs of different robot models on wheels. Beside these is a schematic diagram. A X is the horizontal axis and A Y is the vertical downward axis. The length of A B is L 2, E F is L 6, H G is L 9, D E is L 5, C G is L 8, C D is L 4. B F and G D intersect at point C.

Wheel-legged robot model and structural diagram

The robot needs to constantly adjust its own attitude to maintain the smooth operation of the vehicle body, which requires constant calculation of the E-point coordinates to obtain the deviation of the center of gravity of the body and the height of the body, and change the position of the center of gravity by constantly adjusting the angle of the wheel legs so that it falls on the axes of the driving wheels on both sides. It can be seen from the structure sketch in Fig. 1. To get the height of the robot leg, it is necessary to solve the kinematics of the planar seven-link mechanism of the robot leg.

$$\left\{ \begin{gathered} x_{G} = l_{1} + l_{9} \cos \phi_{5} \hfill \\ x_{D} = x_{G} - (l_{4} + l_{8} )\cos \phi_{7} \hfill \\ x_{E} = x_{D} + l_{5} \cos \phi_{3} \hfill \\ {\text{y}}_{B} = l_{2} \sin \phi_{1} \hfill \\ {\text{y}}_{F} = {\text{y}}_{B} + (l_{3} + l_{7} )\sin \phi_{2} \hfill \\ {\text{y}}_{E} = {\text{y}}_{F} + l_{6} \sin \phi_{4} \hfill \\ \end{gathered} \right.$$
(1)

The coordinates of point E can be solved by calculation:

$$\left\{ \begin{gathered} x_{E} = l_{1} + l_{9} \cos \phi_{5} - (l_{4} + l_{8} )\cos \phi_{7} + l_{5} \cos \phi_{3} \hfill \\ {\text{y}}_{E} = l_{2} \sin \phi_{1} + (l_{3} + l_{7} )\sin \phi_{2} + l_{6} \sin \phi_{4} \hfill \\ \end{gathered} \right.$$
(2)

3 System Design

The system adopts the balance ring, speed ring and steering ring in series, and the speed of the wheel legs is controlled by the current ring of the control motor, as shown in Fig. 2, which shows the program structure of the wheel-legged robot system.

Fig. 2
A block diagram of a 2-legged robot model. It is equipped with leg balance ring P I D, speed P I D, current pitch angle, balanced loop fuzzy P I D, current pitch angle, steering ring P I D, joint driven steering gear, speed ring P I D, current Z axis angular velocity, C 620 controller, and M 3508 motor.

Program structure of wheel-legged robot system

3.1 Conventional PID Control

The left and right side joints of the robot use digital motors with position control, and the wheeled motion uses the PID control method to design the robot movement and steering motion controllers respectively. The wheeled motion motor control adopts the classic three-loop PID control method, the innermost loop is the balance loop, which adopts fuzzy control, and controls the balance of the body by reading the BMI088 attitude sensor data for PD operation; The second ring is the speed ring, which realizes the control of the motor speed by performing PI operation on the motor speed feedback deviation; The outermost ring is the position ring, which realizes the control of the motor position by performing PD operation on the motor position feedback deviation. The height change of the car body is controlled by fuzzy PID, the system monitors the height of the car body in real time and changes the PID parameters to adapt to the balance of the car body of different heights.

The input–output relation equation of the PID controller is:

$${\text{u}}(t) = K_{p} e(t) + K_{i} \int\limits_{0}^{t} {e(t)} dt + K_{d} \frac{de(t)}{{dt}}$$
(3)

where Kp is the scaling factor, Ki is the integration factor, Kd is the differentiation factor, and e(t) and u(t) are the input and output quantities respectively.

The driving wheel is a DC brushless motor, the robot speed loop control is mainly through the measurement of the rotational speed values of the wheels on both sides, the calculation of the difference between the actual speed of the wheel-legged robot and the theoretical speed, low-pass filtering of the speed deviation, filtering out the high-frequency interference, preventing the speed of the sudden change, so as to make the waveform smoother and the operation more stable, and finally according to the output of the difference to change the real-time speed of the robot, the calculation formula is shown in Eq. (4):

$$ Speed\_Out = Kp \times {Speed\_Err\_Lowout} + Ki\,\times\,{Speed\_Integral} $$
(4)

The wheel-legged robot steering loop control calculates the difference between the forward direction of the robot and the theoretical steering angle through the yaw angle and yaw angular velocity, and changes the steering of the wheel-legged robot according to the output difference, which is calculated as shown in Eq. (5):

$$Turn\_Out = Kp \times (Target - Angle) + Kd \times gyro$$
(5)

The wheel-legged robot leg control calculates the difference between the robot body angle and the horizontal angle through the pitch angle and the pitch angle velocity, and changes the body tilt angle of the wheel-legged robot according to the output difference to keep the wheel-legged robot body in a horizontal state, and the calculation formula is shown in Eq. (6):

$$Height\_Out = Kp \times (Pitch - Target) + Kd \times gyro$$
(6)

3.2 Adaptive Fuzzy PID Control

According to the control requirement of variable height adaptive, the fuzzy adaptive PID control of wheel-legged robot is realized by changing the PID coefficient factor. The main design idea is that the system obtains the body inclination error according to the difference between the data of BMI088 attitude sensor and the set equilibrium angle, and takes the error e and the rate of change of the error ec as the inputs, ΔKp, ΔKi, ΔKd as the outputs, and uses the fuzzy control rules to regulate the PID parameters so as to realize the purpose of adaptive control. The parameters of the traditional pid are fixed values, and not the adjusted parameters are the best parameters, while the fuzzy adaptive PID has the advantage of flexibility and stability, especially for the variable height wheel-legged robot, which is a large time-varying and nonlinear controlled object, its advantages are more prominent.

According to the advantages and disadvantages of fuzzy adaptive control and traditional PID, this paper combines the advantages of the two to achieve optimal control, such as Fig. 3 shows the composite structure of fuzzy PID and traditional PID.

Fig. 3
A block diagram. E of t is input to K e followed by two dimensional fuzzy controller. E of t is also passed through d e by d t and P I D controller. d e by d t is followed by K e e and two dimensional fuzzy controller. The outputs are added and led to controlled object to obtain y of t.

Fuzzy PID and conventional PID composite structure

According to the characteristics of the control system of the wheel-legged robot, the angle value measured by the angle sensor and the theoretical value at the time of balancing are used to find out the deviation e, and the deviation is derived to obtain the deviation rate of change ec, and the deviation e and the deviation rate of change ec are used as the input values of the system, and since the balancing loop adopts the fuzzy PD control, the Kp and the Kd are used as the output parameters of the fuzzy control. In order to ensure the stability of the wheel-legged robot and the safety of the body in the face of unexpected situations, the maximum controllable angle is specified as [-24°,24°], the input linguistic variable parameters of the system are set as E and EC, and the output linguistic variable parameter is set as U. The thesis domain of the deviation E is {NB, NM, NS, Z, PS, PM, PB}, and then the quantization factor is K1=0.25. According to the body simulation graph and the actual body swing, the value range of ec is determined as [-3,3]rad/s, and the same set the thesis domain of EC as {NB, NM, NS, Z, PS, PM, PB}, then the quantization factor is K2=2.

Fuzzy inference rules are developed using Simulink simulation toolbox. Based on the engineering experience, the fuzzy rule table as shown in Tables 1 and 2 is developed.

Table 1 Fuzzy rules for ∆Kp
Table 2 Fuzzy rules for ∆Kd

The Simulink model is built in MATLAB software, the FUZZY submodule is established to realize parameter fuzzification, and the PID submodule completes the PID control operation. As Fig. 4 shows the adaptive fuzzy control output surface diagram. By establishing the fuzzy theory PID control system simulation model helps to improve the stability and robustness of the control system of the wheel-legged robot.

Fig. 4
Two 3 D surface graphs. Left. It plots k p versus e c versus e. It plots a descending color graded gridded surface between negative 3 and negative 60. Right. It plots k d versus e c versus e. It plots an upward opening color graded gridded surface between negative 20 and 20.

Kp and Kd output surface

4 Experimental Analysis

In this paper, ADAMS and MATLAB joint simulation is used to analyze the balance and robustness of the wheel-legged robot. The physical model of the two-wheeled legged robot is built by writing C language program for testing to check the research theory.

4.1 Simulation Analysis

The 3D model of the wheel-legged robot is established by SolidWorks software, imported into ADAMS software to impose constraints and add function relationships, and finally ADAMS software and MATLAB software are used for joint simulation. As Fig. 5 shows the simulation structure of the wheel-legged robot, the left side shows the state of the wheel-legged robot when it descends to the lowest position and the right side shows the state when it rises to the highest position.

Fig. 5
Two robot simulation location maps. A. It has two wheels and an empty plate on the top to carry materials. B. Raised robot legs.

Wheel-legged robot simulation location map

The curve shown in Fig. 6 is obtained through simulation, and the robustness of the wheel-legged robot is examined by adding a disturbance test at the 5th and 10th seconds in the equilibrium state, applying a 0.8 N disturbance force, and the angular velocity in the equilibrium direction produces a sharp oscillation under the disturbance of the external force as shown in Fig. 7, which is quickly restored to the equilibrium state under the regulation of fuzzy control. Figure 8 shows the Roll-Pitch angle change, the body occurred a small angle change, do not affect the balance state of the body. From the 11th to the 20th second during the rise of the body, the yaw angle do not change, keeping the forward direction, the Roll-Pitch angle is adjusted at a small angle, according to the structure of the body and the distribution of the mass of each part, the balance of the body was maintained by adjusting the angle during the balance. From Fig. 9 the body rise height is 550 mm. Figure 10 shows the yaw angular velocity profile which fluctuates near 0 to maintain the stability of the body direction. In Fig. 11, the wheel speeds on both sides keep near 0. The speeds of the wheels on both sides are the same at equilibrium, so the figure shows a unilateral wheel speed curve diagram, and the simulation results show that the wheel-legged robot has good stability and robustness [6,7,8].

Fig. 6
A graph of force in Newton versus time in seconds. 0.8 Newton external force is applied at 5 seconds and 10 seconds and two sharp spikes are obtained.

Apply 0.8 N interference force

Fig. 7
A graph of angular velocity versus time. 0.8 Newtons of external force is applied at 5 seconds and 10 seconds, and two sharp downward spikes are obtained.

Roll angular velocity

Fig. 8
A multiline graph of angle versus time. The body angle roll moves horizontally till 13 seconds after which it descends as a S curve. The body angle pitch first ascends to 0.0009, then becomes horizontal and fluctuates. Steering and balance angles are indicated.

Roll angle and pitch angle

Fig. 9
A graph of length versus time. The car body C M first moves horizontally at minus 100 then ascends after 11 seconds, and again becomes parallel to the horizontal axis after 20 seconds. The initial balance position height is at 11 seconds. The final balance position height is indicated.

Body height

Fig. 10
A graph of angular velocity versus time. The plotted trend is noisy and fluctuates about 0.

Pitch angular velocity

Fig. 11
A graph of velocity versus time. The plotted trend is noisy and fluctuates about 0.

Wheel speed on both sides

4.2 Motion Analysis

On the basis of theoretical research, the construction of the physical model was completed. First of all, the wheel-legged robot motor speed response speed test, Fig. 12 shows the DC brushless motor speed response curve, it can be seen that the wheels can respond very quickly under different speed switching. The velocity response curve of the wheel-legged robot running under no load is shown in Fig. 13. It can be seen from the curve graph that different interference forces are constantly applied to the wheel-legged robot during its operation at different rotational speeds, and the running speed can be recovered in a very short time after being interfered with, which indicates a better velocity response characteristic of the robot as well as a good robustness.

Fig. 12
A multiline graph of velocity versus time. It presents the variations of wheel speed L and wheel speed R. The two response curves originate from (0, 0) and vary in opposite quadrants. They intersect with each other. It indicates the response speed of the vehicle body at different speeds.

Drive wheel motor speed response

Fig. 13
A multiline graph of velocity versus time. It presents the variations of wheel speed L and wheel speed R. The two response curves originate from (0, 0) and vary in opposite quadrants. They intersect at 250 seconds. Different external forces to the vehicle body at different speeds are applied.

Wheel speed under interference force

In the equilibrium state, Fig. 14 shows the curves of roll angle and yaw angle of the wheel-legged robot, and Fig. 15 shows the robustness test graph of the wheel-legged robot, which shows that the robot has been subjected to external forces for many times, and the roll angle has been deflected by a large angle relative to the equilibrium state, and it is still able to return to the stable state in a relatively short period of time by continuously adjusting the robot's position, while keeping the roll angle fluctuating up and down in the equilibrium position, and the yaw angle fluctuating up and down in the fixed angle all the time, indicating that the robot's forward direction has not been changed because of the action of the external forces, and it has a higher degree of smoothness and robustness.

Fig. 14
A multiline graph of angle versus time. It presents the variations of angle pitch and angle roll. The two response curves originate from (0, 0) and vary in opposite quadrants. There is almost no change in Yaw angle but changes in rolling angle under external force.

Curve plot of roll angle and yaw angle

Fig. 15
Two photographs of a robot car. It moves on the smooth floor in presence of the interference force.

Applying interference force to test robustness

The wheel-legged robot can adapt to different terrain, mainly by changing the height of the two sides of the wheel legs to keep the body smooth. Figure 16 shows the physical picture of the wheel-legged robot passing through the uneven ground, Fig. 17 shows the output curve of the PWM value of the four drive motors on both sides of the wheel-legged, and Fig. 18 shows the change of the pitch angle of the wheel-legged robot during operation. According to the requirements of the smoothness of the Vehicle body, always keep the center of gravity of the Vehicle body in the lowest state, with the constant change of the body's tilt angle, the PWM output value of the drive motors on both sides of the wheel-legged robot is also changing, adjusting the posture to ensure the balance of the body. The body can realize the lift function through the movement of the two sides of the wheel legs, Fig. 19 shows the process of the wheel-legged robot body rising, this process is mainly through the fuzzy control to realize the smoothness of the body, the two sides of the wheel legs to assist in the control, so that the center of gravity of the projection as far as possible to maintain in the wheel axis.

Fig. 16
Three photographs of a robot. This robot has wheels. It moves in three different directions on an uneven floor.

Wheel-legged robot passes through uneven ground

Fig. 17
A multiline graph of P W M output value versus time. It presents the variations for left A, left B, right C, and right D. The trends have triangular and trapezoidal spikes and intersect.

Drive motor PWM output value

Fig. 18
A line graph of pitch angle value versus time. The trend has 5 peaks above zero line and two troughs below it.

Pitch angle of wheeled legged robot

Fig. 19
Five photographs of a robot present the lifting of its body to the highest level.

Wheel-legged robot body lifting

5 Conclude

This paper focuses on the design of a wheel-legged robot system algorithm based on the fusion control of variable height adaptive fuzzy PID and traditional PID, for the liftable double wheel-leg structure, it is not possible to accurately establish the system model, and it is not suitable for a single control method with a linear model, so the control method of fusion of a linear model and a nonlinear model is used to verify the feasibility of the method, and the experimental results are as follows:

  1. (1)

    The joint simulation model of ADAMS and MATLAB dynamics is established to simulate the situation of the wheel-legged robot being subjected to external interference force during the ascent process, and the simulation results show that the system has high smoothness and robustness through the system algorithm design of fuzzy control fused with traditional PID.

  2. (2)

    The physical model of the wheel-legged robot is constructed for experiments to verify the stability of the body on the complex road surface and the robustness of the body in the equilibrium state and when running at variable speed. The experimental results show that the wheel-legged robot can meet the design requirements and has high robustness and stability.

The controller based on the fusion control of adaptive fuzzy PID and traditional PID has good control effect, which can meet the wheel-leg balancing system with variable center of gravity height, and greatly improves the stability and robustness of the wheel-leg robot. And the system principle is clear, easy to implement, does not need to establish an accurate system model, and can meet the design requirements of modern wheel-legged robot intelligent control system.