Abstract

This paper proposes a lateral balancing structure based on precession effect of double-gyroscopes and its associated control strategy of the steering for an underactuated unicycle robot. Double-gyroscopes are symmetrically designed on the top of the unicycle robot and utilized to adjust the lateral balance of system. Such design can inhibit the disturbance of the gyroscope system to the pitch angle and is beneficial to maintain the lateral balance in the case of large roll angle fluctuations. Based on the analysis of the dynamics model, the gyroscope precession effects will be caused by the angular velocity of the bottom wheel and the roll angular velocity, i.e., resulting in a torque in the direction of the yaw. Then, a rapid response control strategy is proposed to use the torque to control the steering. Simulation results demonstrate the rationality of the lateral balance structure and the feasibility of the steering control method.

1. Introduction

Mobile robots, consisting of sensors and automatically mobile vehicle, are more flexible than other robots. So they are fitted to be used at inaccessible and harmful for people working environment. As one kind of mobile robot, unicycle robots are more flexible due to the single point contact of wheel of robot and ground. Therefore, the unicycle robot has the potential of free movement and moving at narrow spaces.

In most studies of unicycle robot, lateral balance has been emphasized with attention. According to the lateral balance methods, the unicycle robot can be classified into horizontal flywheel [16], vertical flywheel [713], high-speed gyros named Gyrover [1419] and gyro precession with two gyroscopes [20, 21]. However, most of researches focus on balance control and neglect control of steering. If unicycle robot has steering control, it could realize target tracking and avoid obstacles. Some researchers already started to develop steering control method of the unicycle robot. Y. Isomi and S. Majima proposed a method to control unicycle robot’s yaw without direct force for changing the yaw [22, 23]. They derived the dynamics equation of unicycle robot and showed the yaw rate depends on the angular velocity of wheel and the roll angle. Through combining the solved equation of equilibrium state and Kanayama’s tracking control method, it was proposed that the unicycle robot can track a target trajectory by this control method. In their simulation, it was confirmed that their control method can help unicycle robot obtain desired yaw rate. Gong Daoxiong and Li Xinghui also present the unicycle robot’s yaw rate depending on the roll angle and the angular velocity of the wheel [24]. Through dynamics equation they proposed the theory. Then, they set the roll angle and angular velocity of the wheel to show the rate of the yaw direction achieved in simulation. Zhu Xiao Qing et al. added a horizontal flywheel between vertical flywheel and wheel of the unicycle robot [16, 25]. This unicycle robot uses the horizontal flywheel to control yaw angle with LQR controller.

The existing steering control methods for unicycle robot are mainly divided into two categories. One method appended a horizontal flywheel mechanism for yaw angle control. However, the appended horizontal flywheel not only increases the weight of the unicycle robot but also makes the mechanism of unicycle robot complex. For the dynamics and control of the unicycle robot, appended horizontal flywheel will increase the complexity of its dynamic model and disturb the pitch and roll angles because of dynamics coupling. Another method used the dynamics coupling between the roll and yaw angles of the unicycle robot to realize steering control. Nevertheless, roll angle of the unicycle robot is too tiny for steady remaining and to reach a quick response in steering control.

This paper proposes a steering control method by regulating the roll angular velocity. According to the gyro precession effect, if a gyroscope has a spinning velocity and gets a precession angular velocity, there will be a gyroscopic torque by the right-hand rule. The steering control method in this paper regards the bottom wheel as a gyro and the roll angular velocity of the unicycle robot is regarded as the precession of the gyro. This can produce a precession torque in the direction of yaw. With a fixed bottom wheel speed, the yaw angle can be regulated by controlling the roll angular velocity of the unicycle robot.

The differences between the proposed and existing steering control methods for underactuated unicycle robot are as follows. (1) Existing steering control method is based on the vertical flywheel unicycle robot and the steering control method mentioned in the paper is based on precession effect of double-gyroscopes unicycle robot. (2) Existing underactuated steering control method realized steering by controlling the roll angle and the steering control method mentioned in the paper, by controlling the rolling angular velocity, more appropriate according to the dynamic analysis. Also, both of the control methods are simulated and compared in Section 5.

The rest of the paper is organized as follows. In Section 2, equations proving the motion of the unicycle robot are derived. Section 3 analyses the dynamics of pitch, roll, and yaw, respectively. Section 4 shows the control strategies of static and steering. In Section 5, the control strategies are proved by simulation and compared with the existing method. Conclusion and future work are presented on Section 6.

2. Model

2.1. Unicycle Robot

Figure 1 shows the model of unicycle robot. This unicycle robot’s lateral balance is based on gyro precession. This type of unicycle robot has an excellent controllability on its roll angle. It is helpful for controlling angular velocity of roll.

The robot is consisting of two gyroscopes, a gyro precession, a frame, and a bottom wheel. The two gyroscopes have the same spinning velocity but their direction is opposite. Also we use one motor to control 2 of gyro precession to keep 2 of gyro precession the same at angular velocity and opposite at direction. It can inhibit the torque causing by gyro precession at pitch angle.

Figure 2 shows the coordinate system used to describe the posture of unicycle robot. The posture of the robot is given in terms of the roll angle δ, the pitch angle θ, and the yaw angle φ. Table 1 shows the parameters of the unicycle robot.

2.2. Equations of Motion

The dynamic equations of the wheel are derived by the Euler-Lagrange formulation. The Euler-Lagrange equation is

The L in Euler-Lagrange equation is the Lagrangian function. It is defined aswhere K is the kinetic energy of the unicycle robot. It can be represented aswhere , , , , , are kinetic energy of wheel center and frame’s centre of gravity, respectively. , , , are kinetic energy of precession frame’s centre of gravity for left and right. , are kinetic energy of gyro’s centre for left and right.

U is the potential energy of the unicycle robot. From Figure 2, U can be represented as

is potential energy of wheel centre. is potential energy of frame’s centre of gravity. and are potential energy of precession frame’s centre of gravity for left and right. and are potential energy of gyroscopes’ centre for left and right.

Q and q are the generalized forces and generalized coordinates, respectively. For the system, q is selected as

Q is given by

In order to simplify the dynamic equations, and mean and , respectively. Using the Euler-Lagrange equation, the dynamic equation of the system can be given by

where and are the inertia matrix and nonlinear term, respectively.

The dynamic equations of the unicycle robot are far too lengthy to be shown here due to space limitations. Therefore, the reader is referred to in the Appendix. The dynamic equations are complex for control design and they have strong coupling. In order to derive the control strategy of static and steering, we need to simplify the model. According to the steady motion characters of unicycle robot, the dynamic equations of the system are decoupled and simplified to three parts. They are pitch dynamics, roll dynamics, and yaw dynamics, respectively.

3. Analysis on the Dynamics

3.1. Dynamic Model for Pitch Axis

The robot frame and the precession system can be seen as a single body, and the pitch dynamic of the system can be regarded as a wheeled inverted pendulum system. Both of roll angle and yaw angle change are small and can be neglected. The dynamic equations for pitch are derived from Lagrange’s equation as follows:where and . According to (10), the state equation for pitch is as follows:

The coefficients of and are tinier than others. The coefficient of is far less than and . The coefficient of is far less than . These coefficients are ignored. So the simplified dynamic equations about pitch angle are as follows:

From (12) and (13), the dynamic equations are as follows:

where coefficients are

represents the torque of the bottom wheel. C is the gravity component of unicycle robot for pitch. In order to balance of pitch, the torque of the bottom wheel must relate to pitch angle and pitch angular velocity which control the change of pitch angle stable. When the pitch angle tends to zero, the bottom wheel can keep stable. According to the analysis of the dynamics of pitch axis, the design of detailed control strategy is in next section.

3.2. Dynamic Model for Roll Axis

The robot’s frame and the bottom wheel can be seen as a single body, and the roll dynamic of the system can be regarded as a gyroscopic precession system. Both changes of pitch angle and yaw angle are small and can be neglected. The dynamic equations for roll are derived from Lagrange’s equation as follows:where and . According to (17), the state equation for roll is as follows:

The coefficients of are tinier than others. The coefficient of is far less than . The spinning velocity of gyroscopes is constant value, so and . These coefficients are ignored. So the simplified dynamic equations about roll angle are as follows:

represents the torque of the precession system. represents gyroscopic precession moment. The coefficient of represents gravity component of roll. According to (19), the gyroscopic moment provides torque to resist unicycle robot’s gravity component of roll. Besides, the unicycle robot gets an angular acceleration of roll. But gyroscopic moment’s coefficient includes cosine precession angle. It means torque of gyroscopic moment is smaller as precession angle is larger. According to the analysis on the dynamics of roll axis, controlling angular velocity of precession is better than torque of the precession system, and the design of detailed control strategy is in next section.

3.3. Dynamic Model for Yaw Axis

For the yaw dynamic of the system, assume the change of the pitch is small and can be neglected. The roll angle is small so that and can be approximated to zero and one, respectively. The bottom wheel and gyroscopes get a constant speed. The dynamic equation for yaw is derived from Lagrange’s equation as follows:where and . According to (22), the state equation for yaw is as follows:

The coefficients of , are tinier than others. So the simplified dynamic equation about yaw angle is as follows:

In the equation, is the gyroscopic precession moment of bottom wheel and the unicycle robot’s roll angle. According to the equation, influence factor for yaw angle includes the angular velocity of bottom wheel and the angular velocity of roll. The angular velocity of bottom wheel should hold on a constant value for balancing of pitch angle. Therefore, the steering control strategy is designed about the angular velocity of roll, and the design of detailed control strategy is in next section.

Due to the yaw angle coupling to pitch angle and precession angle, the analysis of these 2 angles is necessary in the steering control method. When angular velocities of yaw and the bottom wheel keep stable, the angular velocity of roll will stable to zero and the roll angle is small for being ignored. The dynamic equation for pitch angle is derived as fallows:where and . According to (25), the state equation for pitch is as follows:

The coefficients of and are tinier than others. The coefficient of is far less than . These coefficients can be ignored. So the simplified dynamic equation is as follows:

is the centripetal force for yaw angle’s circle. When the unicycle robot has a yaw angular velocity and the change of pitch angle is stable, the dynamic equation is as follows:

It means centripetal force for yaw angle’s circle also affects pitch angle. When the unicycle robot has a constant yaw angular velocity, the pitch angle is stable at a constant.

Similarly, when the angular velocities of yaw and the bottom wheel keep stable, the angular velocity of roll will stable to zero and the roll angle is small for being ignored. Also the change of pitch is stable. The dynamic equation for precession angle is derived as fallows:where and . According to (29), the state equation for precession is as follows:

So the simplified dynamic equation is as follows:

is the centripetal force for yaw angle’s circle. When the unicycle robot has a yaw angle velocity and the change of precession angle is stable and the torque of precession is stable at zero, the dynamic equation is as follows:

It means centripetal force for yaw angle’s circle also affects precession angle. When the unicycle robot has a constant yaw angle velocity, the precession angle is stable at a constant.

4. The Control Strategies Design

For traditional unicycle robots, their controllers are generally separated at lateral and longitudinal and ignored the yaw angle. However, the above dynamic analysis proved that angular velocity of the yaw affects both of lateral balance and longitudinal balance. Also, yaw angle can be controlled by angular velocity of the roll. In this section, there are two control strategies. First is designed for static balance control from the simplified dynamics of the pitch (14), (15) and the roll (19), (20), and (21). Another is steering control, according to the simplified dynamics of the yaw (24).

4.1. Static Balance Control

Based on the dynamic analysis of the previous section, the unicycle robot’s pitch angle is balanced by the torque of the bottom wheel and roll angle is balanced by the precession system. The torque of the bottom wheel is to regulate the pitch angle θ and the angular velocity of wheel . The spinning velocity of gyroscopes keeps a constant value, and angular velocity controller of precession is adaptive for the balance of roll angle according to the analysis of previous section.

The input of bottom wheel is as follows:where , , , are controller gains. is the difference between the real-time pitch angle and the set angle . It is given as

is the difference between the real-time angular velocity of wheel and the set angular velocity . Its integration is . It is given as

The torque of the bottom wheel includes PD controller of the pitch angle and PI controller of the angular velocity of wheel . The set values , , and are 0 to keep unicycle static for longitudinal.

The input of angular velocity of precession is as follows:where , , are controller gains. is the difference between the real-time roll angle and the set angle . It is given as

is the difference between the real-time precession angle and the set angle . It is given asThe angular velocity of precession includes PD controller of the roll angle and P controller of the precession angle . According to the dynamic analysis of roll angle, the torque of precession system has a coefficient . It means the torque of gyro precession system is smaller as precession angle increasing. So a P controller was designed to return the precession angle to zero. And the set values , , and are 0 to keep unicycle static for lateral. The detailed control block diagram is shown in Figure 3.

4.2. Steering Control

Based on the dynamic analysis of the previous section, the unicycle robot’s yaw angle is related to the angular velocities of roll and bottom wheel. In order to enhance the reaction of steering and the stability of the controller, fast responsive control strategy is opted to steering control.

The input of precession angular velocity is as follows:where , , , , , are defined as static balance control. The differences are and . It is given aswhere is coefficient of fast responsive control strategy for steering control. is the difference between the real-time yaw angular velocity and the set yaw angular velocity . It is given as

Also, according to the dynamic analysis of yaw, it is not only related to the angular velocity of roll, but also to the angular velocity of bottom wheel. In the process of steering control, the bottom wheel gets an angular velocity and the set angular velocity is constant value. The detailed control block diagram is shown in Figure 4.

5. Simulation

In this section, the controllers will be tested by dynamics simulation and all the data and codes of the simulations are available online (see https://github.com/ZhangYang157/01-Codes-and-Data-for-Steering-Control-Method-for-an-Under-actuated-Unicycle-Robot-Based-on-Dynamic-.git) and are included in the supplementary materials (available here). The simulation video for the proposed steering control method is available online (see https://github.com/ZhangYang157/02-supplementary-material-file-for-simulation-video.git). A three-dimensional simulation model of unicycle robot is built in the ADAMS environment. It is shown in Figure 5. The simulation model includes 5 parts. They are ground, gyroscopes, precession, frame, and bottom wheel. Ground is fixed in space. Static friction coefficient between bottom wheel and ground is 0.8 and dynamic friction coefficient is 0.4. According to the control strategies design, the input of the bottom wheel is the torque . The input of precession is angular velocity of precession and the angular velocity of gyro is constant value. The sampling time is 10 ms. In this section, there are two experiments. Firstly, static balance equilibrium is controlling the unicycle robot stable in place with an interference force. Secondly, steering control method of the unicycle robot is setting the roll angular velocity and giving the angular velocity of bottom wheel a constant value.

5.1. Simulation of Static Equilibrium

For the initial state of the simulation, the unicycle robot has a minimal inclination angle for roll and pitch. In the simulation time of 5s, there is a lateral interference force of 10 N (duration is 0.01s). Using the controller of static balance control, Table 2 shows the control parameters value of the static control strategy in simulation. Simulation is generated in 8 seconds. Figure 6 shows the graphs of roll and pitch angle in static balance simulation. The unicycle robot gets to stability at start. In time 5s, the roll angle and pitch angle accordingly vary with the lateral interference force. With the static balance control strategy, the unicycle robot was back to stable.

5.2. Simulation of Steering Control

Based on the static balance equilibrium, the steering control adds an angular velocity of the bottom wheel , fast responsive control strategy for steering. Table 3 shows the control parameters value of the steering control strategy in simulation. The set bottom wheel angular velocity is and the coefficient of fast responsive control strategy is 1.1. Before steering control, the robot is controlled to balance with a given angular velocity of the bottom wheel and the set angular velocity is zero. When the angular velocity of bottom wheel is stable to , the set angular velocity is given.

The simulation experiment also compares the existing under-actuated steering control strategies. As Y. Isomi, S. Majima [22, 23], Gong Daoxiong and Li Xinghui [24] proposed steering control method for unicycle robot; the steering is controlled by the roll angle with the constant speed of bottom wheel. Comparative analysis of the 2 different steering control methods by simulation experiment is next.

The set angular velocity is ramp and the slope is until is . In order to increase input stability of , there is a low pass filter to the set angular velocity before input. Figure 7 shows the set yaw angular velocity of previous filter, the set yaw angular velocity of after filter, the practical yaw angular velocity, the practical yaw angular velocity of existing method, the set yaw angle after filter, the practical yaw angle, and practical yaw angle of existing method. The practical angular velocity of yaw is accurate following the set angular velocity of yaw with a bit of delay at the acceleration. The angle of yaw is increased steadily. Using the coupling of the unicycle robot, the yaw angle is controlled without directly torque for steering. By comparing with existing method, the yaw angle control method proposed in this paper is faster response to yaw angle control command and closer to set yaw angle and yaw angular velocity curves.

Figure 8 shows the graphs of practical roll angle, the practical roll angle of existing method, the practical roll angular velocity, and the practical roll angular velocity of existing method. The angular velocity of roll and roll angle get a big fluctuation since the fast responsive control strategy of steering. When the practical angular velocity of yaw steadied at a constant value, the angular velocity of roll becomes stable again. By comparing with existing method, the control method proposed in this paper has relatively large amplitude, but it is stable to the steady state for roll angle and roll angular velocity faster.

Figure 9 shows the graphs of practical pitch angle, the practical pitch angle of existing method, the practical pitch angular velocity, and the practical pitch angular velocity of existing method. The angular velocity of pitch gets a big fluctuation due to the fast responsive control strategy of steering. When the angular velocity of yaw is going to stabilize, the angular velocity of pitch is stable to zero and the pitch angle is stable to a value due to effect of centripetal force as (28). By comparing with existing method, the control method proposed in this paper is more quickly stable to the steady state for pitch angle and relatively large amplitude for pitch angular velocity.

Figure 10 shows the change of practical precession angle, the practical precession angle of existing method, the practical precession angular velocity, and the practical precession angular velocity of existing method. Through controlling the precession angular velocity, the unicycle robot gets to balance with a short while. The angular velocity of precession is the input for balance of roll angle. When the steering control is going to stabilize, the angular velocity of precession becomes stable to zero and the precession angle is stable to a value due to effect of centripetal force as (32). By comparing with existing method, the control method proposed in this paper is more quickly stable to the steady state for precession angle and relatively small amplitude for precession angular velocity.

Figure 11 shows the angular velocity of bottom wheel . At the beginning, the angular velocity of bottom wheel becomes stable at . has a big fluctuation during the angular velocity of yaw causing a change. When the angular velocity of yaw is steady, is stable at again. The curve “practical of existing method” shows the angular velocity of bottom wheel for the yaw angle control method by roll angle. Both of the angular velocities of bottom wheel are stable at , but the curve of existing method has higher frequency of oscillation than the control method mentioned in the paper.

6. Conclusion

This paper has presented a steering control method for the under-actuated unicycle robot which using precession effect of double-gyroscopes for lateral balance. The proposed method uses the coupling to control the roll angular velocity for steering. The steering control method is proposed through analyzing the dynamic model of the unicycle robot and the fast responsive control strategy is designed with a constant bottom wheel speed. The simulation results demonstrated that the control strategy is effective for steering control. Compared with the existing steering control method, the method mentioned in this paper responds faster to steering commands and tracks the set yaw angle more accurately.

Future works focus on the construction of the experimental platform and the improvement of the performance of the steering control method. More comparative experiments with the existing methods will also be conducted. Meanwhile, the proposed control method will be applied to the autonomous navigation of multiunicycle robots.

Appendix

The coefficients , …… and in the above equations are defined in Table 4.

Data Availability

All the data and codes of the simulations are available online at https://github.com/ZhangYang157/01-Codes-and-Data-for-Steering-Control-Method-for-an-Under-actuated-Unicycle-Robot-Based-on-Dynamic-.git.

Conflicts of Interest

The authors declare that they have no conflicts of interest.

Acknowledgments

This work was supported in part by National Key R&D Program of China under Grant 2017YFF0108000, in part by the National Natural Science Foundation of China under Grant 61473102, in part by the Major Research Plan of the National Natural Science Foundation of China under Grant 91648201, and in part by the Joint Research Fund (U1713201) between the National Natural Science Foundation of China (NSFC) and Shen Zhen.

Supplementary Materials

The data and codes of the simulation for our study are offered by using the zipped file “01-Codes and Data for Steering Control Method for an Under-actuated Unicycle Robot Based on Dynamic Model.zip”. The file “read me.txt” in the zipped file describes each data and codes. The supplementary material file of simulation video is contained at the zipped file “02-supplementary material file for simulation video.zip”. The video is available online. The details can read the file “read me.txt” in the zipped file. (Supplementary Materials)