Keywords

1 Introduction

Quadruped robots provide a highly mobile platform to traverse difficult terrain and are ideal for accomplishing tasks in complex environment. Companies such as Boston-Dynamics, MIT and Ghost-Robotics had presented several medium sized quadruped robots like Spotmini [1], Mini Cheetah [2] and Vision-60 [3], etc. Some of them have been use in unmanned inspection and security. For quadruped robot, the parameter tuning and locomotion experiment on prototype hardware platform is very import. Although there are a lot of high fidelity simulation software, such as pybullet [4] or Webots [5], but the difference between real system and simulation is still difficult to be simulated by computer. Thus, a small and low cost quadruped robot platform for locomotion test can effectively build a bridge between simulation and real system. Moco-Minitaur is a small (sub-3.5 kg), low cost (sub-4500 RMB) 8-Dof direct-drive quadruped robot for dynamic locomotion test. This robot can control vertical and horizontal force and impedance at each foot, and performs stable drop damping, standing and trotting, meanwhile, it can sensitively estimate the touch down status without plantar sensor. This paper introduce how we design its hardware and the control algorithm used for dynamic locomotion (Fig. 1).

Fig. 1.
figure 1

Moco-Minitaur: a low-cost direct-drive quadruped robot for dynamic locomotion

The most mature way to build the low-cost quadruped robot platform is to use 8-Dof parallel legs. Many small quadruped robots use inverse kinematics algorithm to realize the locomotion control, but this method can only ensure the movement at low speed and on the flat ground. For the movement on complex terrain, the force control and impedance control is wildly used in the 12-Dof quadruped robot nowadays. However, those control method has more technical problems while constructing with 8-Dof parallel legs. For example, the X-force and Z-force of 8-Dof parallel legs are coupled, the system is under actuated thus there is no active control of lateral force, which makes it hard to control the roll attitude and rotation at the same time. At present, there are some related research contents, the MIT Super Mini Cheetah [6] can achieve the basic force balance control based on the simplified inverted pendulum model(SLIP). The Standford Doggo [7] can achieve a basic trot gait based on the inverse kinematics algorithm, which uses PD controller on brushless motor to simulate the spring to realize walking on the different terrain. The one with the most excellent ability to move in complex terrain int 8-Dof quadruped robot is the Ghost-Robotics Minitaur [8], it use the SLIP model construct the feed-forward signal and use the force feedback control to achieve better control performance in trot, bound and pace gait. Besides, there are many others 8-Dof quadruped robot design, but most of them just focuses on the design of mechanisms [9, 10].

This paper introduces the mechanisms design and the force impedance control algorithm of Moco-Minitaur. In order to solve the problem of under-actuated and control output coupling, a virtual model controller(VMC) is constructed which effectively reduce the system dimension, its virtual control output can be decomposed based on the optimal allocation algorithm and generate the expected force of each support leg. Meanwhile, a robust impedance force tracking controller(IMP) is designed, which guaranteed the 8-Dof leg can generated desired force under complex contact situations. The experiments proved this low cost robot can realize dynamic locomotion in standing and trotting. Since the total cost of Moco-Minitaur is less than 4500 RMB, and only manual tools are needed to complete the assembly, therefore it can meet the demand of low-cost platform in the future of foot robot motion control and education.

2 Method

2.1 Quadruped Robot Design

The hardware of Moco-Minitaur is open source [11]. The project includes all CAD structure documents, detailed material and assembly wiring introduction and basic software. The total cost of it is less than 4500RMB. The leg structure of Moco-Minitaur is shown in the Fig. 2, the width of the robot is 137 mm, the length is 270 mm, and its weight is less than 3.5 kg. The design of direct-drive motor and leg structure are under the premise of meeting the basic locomotion test and force control requirements of quadruped robot.

Fig. 2.
figure 2

The CAD structure of the Moco-Minitaur robot (L1 = 55 mm, L2 = 110 mm)

The electrical system of Moco-minitaur mainly includes a STM32 microprocessor, two motors of each leg are drove by an Odrive [12], in addition, there is a power management module to realize remote power switch. Compared with Doggo's electrical system design, Moco-minitaur use an STM32F4 microprocessor to convert the ODrive’s ASIIC serial protocol to CAN bus protocol. The main CPU running the FreeRTOS operating system, and realizes the VMC control, swing trajectory planning and impedance control. The controller can calculate torque feed forward command, desired angle and joint PD parameters to each ODrive at 500 Hz, and ODrive completes the FOC control with the frequency of 10 kHz (Fig. 3).

Fig. 3.
figure 3

Electrical diagram of Moco-Minitaur robot

According to the functional requirements of low-cost quadruped robot development platform, it can be seen that direct-drive or small reduction ratio can ensure precise force control, meanwhile, the robot can detect touch down collision accurately and quickly [8]. The comparison between Moco-Minitaur and other low-cost 8-Dof quadruped robot is shown in the Table 1.

Table 1. Comparison of low cost 8-Dof quadruped robot

2.2 Control System Design

The locomotion control algorithm adopted by Moco-Minitaur combines force and impedance control. Basing on the virtual leg theory and decoupling theory of Marc.Raibert [13] the VMC controller and force distribution algorithm are adopted to generate appropriate desired foot force. The control logic block diagram is shown in Fig. 4. Firstly, in order to improve the rotation ability a pose command planner is designed here, which calculate the desired roll attitude and steering angular velocity according to the remote control command, thus the left and right side legs’ swing end position can be get base on capture point theory; Next, the VMC controller will decouple the system as height, forward speed and attitude, and generate the virtual force and virtual torque on body; Finally, the virtual control output will be dis to the supported legs based on virtual leg and least square method, in order to track the desired force in different contact situation, a robust impedance controller is designed base on Jacobian inverse kinematics.

Fig. 4.
figure 4

VMC and IMP control diagram of diagram robot

  1. A.

    Attitude/Position/Speed Command Planner

Due to 8-Dof leg structure is under-actuated, the leg can not generate active lateral force for roll and yaw attitude movement. It is difficult to meet the physical constraints of this system for all dimension force control. Therefore, the passive lateral force can be generated by given roll attitude command as shown in Fig. 5(1). Meanwhile, the yaw rotate motion can be realized based on the differential steering model as shown in Fig. 5(2).

Fig. 5.
figure 5

Pose command planner

Figure 5(1) is the rear view of the robot, we can given the roll attitude command \(\varphi_{d}\) to generate the passive lateral force. Since the leg can only generate the active force in {H}, therefore the passive lateral force \(F_{*,y}^{{\{ N\} }} ,F_{*,z}^{{\{ N\} }} ,* = L,R\) in {N} can be calculated:

$$ \left\{ {\begin{array}{*{20}l} {\varphi_{d} = K_{1} \cdot \frac{{F_{y} }}{2} + \varphi_{yaw} , - \varphi_{\max } < \varphi_{d} < \varphi_{\max } } \hfill \\ {\varphi_{yaw} = K_{2} \cdot T_{z} } \hfill \\ \end{array} } \right. $$
(1)

Where \(\varphi_{\max }\) is the maximum roll attitude command, \(K_{1} ,K_{2}\) are the gain parameters, \(F_{y}\) is the desired lateral force in {N}, \(T_{z}\) is the desired rotate torque in {N}.

Figure 5(2) is the top view of the robot, since the 8-Dof leg structure can only control the yaw rotation based on forward foot force, in order to reduce this control output the differential steering model is used:

$$ \left\{ \begin{gathered} V_{L,x} = V_{x,d} + \frac{{\omega_{z,d} \cdot W}}{2} \hfill \\ V_{R,x} = V_{x,d} - \frac{{\omega_{z,d} \cdot W}}{2} \hfill \\ \end{gathered} \right. $$
(2)

Where \(V_{x,d}\) is the desired forward speed, \(W\) is the width of robot, \(\omega_{z,d}\) is the desired yaw rotate speed, thus the swing end position of each legs can be calculated with capture point theory:

$$ p_{i} = p_{hip,i} + \frac{{T_{s} }}{2}V_{x} + \sqrt {\frac{{P_{z} }}{g}} (V_{*,x} - V_{x} ),* = L,R $$
(3)

Where \(p_{hip,i}\) is the hinged position of each leg in {B}, \(T_{s}\) is the stance time, \(P_{z}\) is the height of robot, \(V_{x}\) is the forward speed, \(g\) is acceleration of gravity.

  1. B.

    Virtual Model Controller

Based on the planner command, three PD controller are used to stable the speed, height and attitude of virtual rigid body:

$$ \left[ {\begin{array}{*{20}c} {F_{x} } \\ {F_{y} } \\ {F_{z} } \\ \end{array} } \right] = \left[ {\begin{array}{*{20}c} {K_{x} (V_{x,d} - V_{x} ) - D_{x} \dot{V}_{x} } \\ {K_{y} (V_{y,d} - V_{y} ) - D_{y} \dot{V}_{y} } \\ {K_{z} (P_{z,d} - P_{z} ) - D_{z} \dot{V}_{z} } \\ \end{array} } \right],\left[ {\begin{array}{*{20}c} {T_{x} } \\ {T_{y} } \\ {T_{z} } \\ \end{array} } \right] = \left[ {\begin{array}{*{20}c} {K_{\varphi } (\varphi_{d} - \varphi ) - D_{\varphi } \omega_{x} } \\ {K_{\theta } (\theta_{d} - \theta ) - D_{\theta } \omega_{y} } \\ {K_{\gamma } (\gamma_{d} - \gamma ) - D_{\gamma } \omega_{z} } \\ \end{array} } \right] $$
(4)

Based on the virtual torque and virtual force generated by VMC controller, the system can be decoupled. Furthermore, the virtual control output should map to the real support legs. For this goal, the Mini-Cheetha uses QP optimization [2] to obtain the optimal results. Since the Moco-Minitaur just uses low-cost microprocessor, which can not meet the real-time calculation ability of solving QP problems. Therefore, this paper uses the virtual leg theory combined with the least square solution to realize the real-time force mapping.

$$ \left[ {\begin{array}{*{20}c} {F_{x} } \\ {F_{z} } \\ {T_{x} } \\ {T_{y} } \\ {T_{z} } \\ \end{array} } \right] = \left[ {\begin{array}{*{20}c} 1 & 0 & 1 & 0 \\ 0 & 1 & 0 & 1 \\ 0 & {p_{L.y} } & 0 & {p_{R.y} } \\ {p_{L.z} } & { - p_{L.x} } & {p_{R.z} } & { - p_{R.x} } \\ {p_{L.y} } & 0 & { - p_{R.y} } & 0 \\ \end{array} } \right]\left[ {\begin{array}{*{20}c} {F_{L,x} } \\ {F_{L,z} } \\ {F_{R,x} } \\ {F_{R,z} } \\ \end{array} } \right] = Ax $$
(5)

The result of force mapping under the support of two legs is \(x = \left( {A^{T} A} \right){\kern 1pt}^{ - 1} A^{T}\). For the typical 4-legged standing, we can use the virtual leg theory to calculate the LF and RH leg force \(x_{LF,RH}\) based on formula (5), and RF and LH foot force \(x_{RF,LH}\) too. According to the virtual leg theory, the diagonally legs can be simplified as one virtual leg, then the final leg force can be calculated by the mean value of the two virtual legs mapping results and compensate the Z-axis force output of the roll:

$$ x_{i} = (\frac{{x_{LF,RH,i} }}{2} + \frac{{x_{LF,RH,i} }}{2})/\cos (\beta ) $$
(6)
  1. C.

    Force Impedance Controller

Firstly, the force feed-forward torque command of motor can be calculated based on the below formula:

$$ \tau_{f} = - J^{T} F $$
(7)

However, the force feed-forward control can not guaranteed in the real robot. Taking Mini-Cheetha as an example, those medium-sized quadruped robots mainly uses WBC [2] and other dynamic optimization algorithms to realize the robust force tracking. However, this kind of algorithm requires a high-precision model of the system and require high computational power. Therefore, Moco- Minitaur uses Jacobian inverse kinematics impedance control to achieve the robust force tracking, which can reduce the amount of calculation and ensure foot force tracking accuracy.

Fig. 6.
figure 6

Robust force impedance controller

As shown in Fig. 6, it can be seen that the final torque command sent to FOC controller consists of impedance command and force feed-forward command, so as to realize active impedance control, the control system can be construct as follows:

$$ \left\{ {\begin{array}{*{20}l} {f = K_{q} (q_{d} - q) + D_{q} (\dot{q}_{d} - \dot{q}) + M_{q} (\ddot{q}_{d} - \ddot{q})} \hfill \\ {\tau_{q} = - J^{T} f} \hfill \\ \end{array} } \right. $$
(8)

Where \(M_{q}\) is the kinetic coefficient, it can be eliminated in the actual closed-loop system, \(q_{d}\) is the desired joint angel and \(\dot{q}_{d}\) is the desired joint angular velocity. Those joint control signal can be converted with the virtual force and torque generated by the VMC controller, and generate the expected speed of each foot as follows:

$$ \begin{gathered} \left\{ {\begin{array}{*{20}l} {v_{i,x} = K_{vx} (F_{x} + \frac{{T_{z} }}{{m_{i} \cdot 2 \cdot W}})} \hfill \\ {v_{i,z} = K_{vz} (F_{z} + \frac{{T_{x} }}{{n_{i} \cdot 2 \cdot W}} + \frac{{T_{y} }}{{l_{i} \cdot 2 \cdot H}})} \hfill \\ \end{array} } \right. \hfill \\ \begin{array}{*{20}c} {where} & {\left\{ {\begin{array}{*{20}l} {\begin{array}{*{20}c} {if} & {i = R} & {m_{i} = - 1,n_{i} = 1} \\ \end{array} } \hfill \\ {\begin{array}{*{20}c} {else} & {m_{i} = 1,n_{i} = - 1} \\ \end{array} } \hfill \\ \end{array} } \right.,\left\{ {\begin{array}{*{20}l} {\begin{array}{*{20}c} {if} & {i = F} & {l_{i} = 1} \\ \end{array} } \hfill \\ {\begin{array}{*{20}c} {else} & {l_{i} = - 1} \\ \end{array} } \hfill \\ \end{array} } \right.} \\ \end{array} \hfill \\ \end{gathered} $$
(9)

Where R is the right side leg and F is the front side leg. Finally, the foot movement speed can be transformed into the desired angle and angular velocity based on Jacobian inverse kinematics:

$$ \left\{ {\begin{array}{*{20}l} {\dot{q}_{d} = - J^{ - 1} \cdot v_{x,z} } \hfill \\ {q_{d} = \int {\dot{q}_{d} dt,q_{\min } < q_{d} < q_{\max } } } \hfill \\ \end{array} } \right. $$
(10)

3 Experiments

In order to verify the dynamic locomotion ability of Moco-Mnitaur robot and whether the proposed control algorithm can solve the dimension reduction decoupling problem in 8-Dof leg structure. Several experiments are designed in this paper, including typical stand and trot gait, uneven ground and step terrain of 8-DOF quadruped robot. Some experiment video can be checked on https://www.bilibili.com/video/BV1pX4y1g7sa.

3.1 Damping Control During Dropping

Firstly, the drop experiment is tested. In the experiment, the robot is released from a height of 10 cm to test the effectiveness of the proposed force impedance racking controller, the drop experiment is shown as follows:

Fig. 7.
figure 7

Drop damping experiment

As can be seen in Fig. 7, it can be seen that the robot enters the stance force control after contact ground, the pose of robot can be stabled based on the impedance and VMC controller. The data curve of this experiment is shown as follows. As shown in this figure, the red dotted line is the expected signal and the black line is the actual value. The robot's entry force control after contact. It can be seen that the maximum Z-direction impact force is less than 10 N. After damping, the robot can resume standing (Fig. 8).

Fig. 8.
figure 8

Curve of drop damping experiment

3.2 Pose Control During Standing

Further experiments are designed to test the typical four legged standing gait. In the experiment, the desired attitude is tracked based on the proposed VMC and impedance controller. the experimental curve is as follows (Fig. 9):

Fig. 9.
figure 9

Curve of standing experiment

3.3 Locomotion Control During Trotting

Finally, the dynamic locomotion test for uneven ground without any plantar sensor is designed. Firstly, the robot need to pass through a 1 cm obstacle (Fig. 10):

Fig. 10.
figure 10

Trot locomotion pass 1 cm obstacle

It can be seen from the above figure that the robot can effectively reduce the impact based on the proposed algorithm. In the process of passing through the obstacle, the body posture is stable, there is no violent fluctuation. The proposed algorithm can meet the requirements of dynamic locomotion, and further tests are carried out on a up-stair experiment:

Fig. 11.
figure 11

Trot locomotion up-stair experiment

As shown in Fig. 11, based on the proposed algorithm, the robot can realize a stable blind up-stair trotting, the proposed control method can realize the dynamic motion control ability in complex terrain。

Fig. 12.
figure 12

Curve of up-stair experiment

In Fig. 12, the green line in the pitch axis curve is the estimated terrain angle. It can be seen that based on the proposed algorithm the robot's attitude disturbance is small when it comes to the stair. The height and forward speed can immediately recover after the disturbance. Therefore, the proposed algorithm effectively solves the under-actuated and output coupling of the 8-Dof leg structure.

4 Conclusion

In this work we introduce Moco-Minitaur robot, a low-cost direct-drive quadruped robot for dynamic locomotion is proposed. We proposed a simple control method combine the VMC and impedance control algorithm, which can realize the dynamic locomotion in complex terrain. The proposed state-of-the-art legged robot platform can improve research and education in legged robotics by lowering the barriers to entry.