Planning Motivation Control

Algorithms for stabilization and flight control of a quadcopter. Development of angular stabilization of a quadrocopter Equation of motion of a quadrocopter on a given course

"QUADROCOPTER FLIGHT CONTROL SYSTEM AND TRAJECTORY PLANNING BY OPTICAL ODOMETRY METHODS ..."

- [Page 2] -

offline or offline mode and online or offline mode. The first mode generates a path using a B-spline from the beginning to the target, laid in an environment with known obstacles, that is, a known static environment is assumed. The online planner plots additional points on the generated trajectory, obtained by the radar, which provides information about the position of obstacles. This method is an example of combining local and global methods. The authors mention that the algorithm can be used to operate in real time.


As it turned out, in practice, comparing all methods of planning a flight trajectory is a difficult task: it all depends on the mission of the flight.

The global method allows solving the problem of generating the trajectory in a general form, and for each special moment of the flight, for example, avoiding obstacles, a local method is connected. This combination makes the toolpath generation algorithm versatile.

1.2.2. Hardware for the implementation of control systems

Defining the geometric path is only one part of path planning, and its implementation depends on the hardware. As discussed above, the main trajectory planning hardware is:

encoders;

inertial sensors;

technical vision systems;

trajectory generation based on data from navigation and location systems GLONASS or GPS.

Encoder based mobile wheeled robot positioning is widespread. They attract with their simplicity, but at the same time have a number of disadvantages associated with the accuracy and frequency of measurements, and cannot be used for aerial and marine robots. Therefore, we will restrict ourselves to considering the remaining means, their advantages and disadvantages.

Inertial sensors. With the development of micro- and nanotechnology, trajectory planning methods based on inertial sensors have become very common. This also applies to small unmanned aerial vehicles like a quadcopter.

Inertial sensors typically include microelectromechanical gyroscopes, accelerometers, and sometimes magnetometers. In theory, these sensors provide all the position information you need. But MEMS rotation sensors primarily work when Coriolis forces occur and show not the angle of rotation, but the angular velocity. This raises the need for integration in the case of an analog signal and summation in the case of a discrete signal. As a result, the indirect measurement of rotation will be approximate and depend on the sampling rate of the signal, since in the end the output signal needs to be digitized.

Another source of error in rotation signals is the manifestation of zero drift in the gyroscope, a phenomenon when, even with a static position, a change in the angle at the output of the gyroscope is shown.

An accelerometer is used to estimate the linear distance traveled. It allows you to determine the magnitude of the linear acceleration. But accelerometers are susceptible to high-frequency and high-amplitude interference, which can be overcome using additional filters (for example, the Kalman filter). As a result of filtering, the signal is also integrated to obtain the value of the traveled distance, which causes an error.

Optical odometry is the process of obtaining position information using cameras and camcorders. This method belongs to the algorithms of technical vision systems. As a result of optical odometry, information is obtained about the distance traveled and the direction of travel. The optical odometry algorithm consists of a sequence of steps, such as image acquisition and its correction, detection of key target points depending on the selected recognition algorithm, verification of optical flow vectors and determination of the movement of the camera carrier (UAV). The disadvantages of this method are the uncertainty in images of the same type and the need for significant computing power.

Application of navigation systems. This method focuses on satellite technology, which allows distance measurement and positioning (in the case of tracking). The satellite signal is available almost everywhere on the surface of the earth. Unfortunately, the registered accidents show that in 15% of cases the causes of unmanned aerial vehicle accidents are the loss of communication and the accuracy of the satellite navigation system, the quality of which directly depends on the number of available satellites. Also, the quality of measurements depends on the location and inclination of the satellite's orbit relative to the Earth. The newest satellites determine the location with an accuracy of 60 cm to one meter.

Features of the flight trajectory planning structure 1.3.

quadrocopter The aim of the study is to achieve full autonomous flight. This task includes three interrelated sub-tasks:

planning a mission, generating the corresponding trajectory and controlling the flight of the quadcopter along the resulting trajectory.

Flight mission planning. At this stage, it is determined which method is appropriate: global or local. At the same time, the tasks that need to be solved in accordance with the chosen approach are also sorted.

The global trajectory planning method can be applied to a quadcopter used for patrolling, control point flight, building inspection, etc. Local planning method, used for quadcopter used for indoor inspections of buildings, in dynamic and changing flight environments, for tracking a mobile agent, avoiding obstacles, etc. Both methods are implemented by analytical comparison with the pilot's behavior: taking into account the final destination (target), the pilot plans a common trajectory (global planning), which must be tracked to the destination and avoided known obstacles.

Due to the likelihood of inaccuracy in the information provided to the pilot, he pays less attention to the information already provided and uses more reliable operational local information to solve possible problems and problems that are actualized during the flight (local planning).

Trajectory generation. In accordance with the chosen planning method, the trajectory generator determines the optimal flight curve and transmits the coordinates as a control task to the autopilot. The generation methods, as discussed in the literature review, are different. They are directly related to the planning method.

Direct and pseudospectral placement methods have one thing in common: dynamics are represented at discrete points along the trajectory. This allows continuous optimization in a discrete nonlinear programming problem using approximating polynomials of various shapes.

The direct placement method is used to check the accuracy of states between discrete nodes obtained by approximating polynomials. However, it imposes additional restrictions on nonlinear programming. These limits are in addition to the processing power requirements. In addition, nonlinear solutions are less accurate than analytical derivative methods.

The final sampling step should be chosen very carefully, since the accuracy of the solution of the derivatives directly affects the speed and accuracy of the optimal solution.

Neural network approximation methods eliminate the need for location method and perform numerical or automatic derivative calculations by approximating dynamics with a neural network for a short, specified period of time. After that, the trajectory is constructed recursively. However, this method does not provide the required performance, since neural networks are based on a heuristic learning method. Hence, neural network approximations are recommended for generating trajectory in a previously known static environment.

Search methods are faster than the aforementioned algorithms, but the local minimum problem is their big drawback.

Flight control. To perform the control task, it is necessary to regulate the flight states in accordance with the given coordinates.

The flight states include six degrees of freedom: three rotational and three translational movements: along the pitch axis, the pitch angle and translational movement are controlled; along the roll axis, roll angle and translational movement; along the yaw axis, the yaw angle and flight altitude are controlled. Two approaches are used to simulate the flight control system: linear and non-linear.

In linear modeling, the control laws are determined in an ideal way, where the flight states are not interrelated, while in the nonlinear model of a quadcopter, trigonometry of small angles is taken into account, sometimes the position of the center of gravity and flexibility of the quadcopter structure are also taken into account.

The literature reflects two approaches to UAV control, they are based on linear nonlinear modeling. As discussed earlier, in the linear approach, the autopilot control algorithm is based on linear quadratic control (LQR), and LQR, optimized using the Kalman filter.

In addition, artificial intelligence-based algorithms are used to control the quadcopter along a given trajectory, including fuzzy logic, varieties of neural networks, and even combined neuro-fuzzy controllers.

The mathematical model of the quadcopter is linear.

AI-based flight state controllers have the advantage of adapting to changes in the flight environment. The real-time control process may not meet the criterion of optimality in terms of speed, especially with a non-linear approach to modeling.

With a linear approach to simulating a quadcopter, four autonomous control loops are obtained, which leads to the fact that a change at the output of the rotational or translational motion loop does not affect the remaining control loops. This assumption is made to justify the choice of a modal control algorithm for the synthesis of flight state controllers.

A more realistic approach to modeling and controlling a quadcopter is to represent the control loops as interconnected. In this case, a change in any value in the internal (rotary motion) or in the external control loop (translational motion) causes changes in all other circuits.

The above approach is more complex for the formation of laws of state change, as well as for the synthesis of a control system.

There are studies examining the influence of the center of gravity position on UAV control. This is important for vertical takeoff and landing aircraft and, in particular, for a quadrocopter, since the entire feedback system is based on inertial control sensors (gyroscope, accelerometer).

Flight trajectory planning system requirements and 1.4.

quadcopter control Currently, the standard for the synthesis of navigation and flight control systems must meet the criteria of the fifth generation for aircraft:

stealth, high maneuverability, advanced avionics based on artificial intelligence and the ability to carry out multipurpose flight.

For a quadcopter, stealth or stealth during flight are not the main criteria, since its flight range is limited.

However, the requirements for a navigation, trajectory planning and control system are high. This is due to the instability of the quadcopter during flight, which is confirmed by the number of registered accidents.

According to the statistics of the US military on the safety of UAVs, the current number of accidents of these systems exceeds by 100 times the number of accidents of manned aircraft. According to other statistics, the probability of an accident for American commercial aircraft in US airspace is 0.06 per million flight hours, and the probability for a Global Hawk UAV is

increases to 1600 per million flight hours. The reasons for these accidents are different. The diagram (Fig. 1.2) shows the causes of failures and accidents of American military UAVs.

- & nbsp– & nbsp–

It follows from the statistics that the UAV control area has the greatest number of problems, summing up the operational probability with the control and communication probability (54% in total). Therefore, from the point of view of robotization of flight, we can conclude that by solving the problems of autonomy and control of the UAV flight, it is possible to reduce the probability and number of accidents. Autonomy here refers to trajectory planning and tracking using on-board automatic control systems.

Quadrocopters have the worst technical endurance among all types of UAVs. Consequently, technical reasons and controls can be significant threats to quadcopter flight.

This justifies the relevance and necessity of researching these miniature rotary-wing aircraft in order to achieve optimal flight autonomy and control of quadcopters.

As a result, the main requirements for trajectory planning and flight control systems are as follows:

intelligence and adaptability of the control system, optimal in terms of stabilization and performance;

the ability to plan and generate a trajectory for various flight tasks;

no influence of the loss of communication on the planning of the trajectory.

As can be seen from the above, there is no universal approach to planning the flight trajectory, and the limitations that occur are caused by the shortcomings of the planning algorithms.

Therefore, we focus on developing a planning algorithm suitable for local and global planning. This can be done on the basis of a technical vision system (STZ), with the help of which the quadcopter performs two tasks:

1) global planning: flight by control points, the quadcopter follows the coordinates determined before the flight;

2) local planning: the quadcopter tracks the mobile agent by color marker.

1.5. Chapter Conclusions

1. An analysis of the methods for realizing the autonomy of a UAV flight shows that at present there are various kinds of trajectory planning algorithms, the level of efficiency of which is largely determined by the flight mission. The developed algorithms allow generating flight coordinates in the local or global trajectory planning mode, which does not allow achieving the universality of their implementation.

2. Analysis of flight control approaches revealed that two modeling approaches are used to obtain control laws: ideal linear and real nonlinear. The peculiarity of the application of the nonlinear model consists in the development of optimal position controllers. As a result of studying various models of a quadrocopter, it was found that the influence of the shift of the center of gravity of the quadrocopter and gyroscopic effects on flight stabilization was not taken into account.

3. To develop methods for planning a flight trajectory based on a vision system, auxiliary navigation systems are used to determine the position, which is due to the dependence of the UAV on the accuracy and availability of auxiliary systems.

4. Based on the analysis of approaches to control and planning of the UAV flight trajectory, the goal of the thesis was determined, which is to develop a mechatronic system capable of effectively controlling the flight of a quadrocopter, taking into account the shift of the center of gravity from its ideal position based on optimized fuzzy controllers by the particle swarm method, so as to track a mobile marker taking into account the probability of recognition uncertainty without auxiliary navigation systems using optical odometry methods.

CHAPTER 2. IDENTIFICATION AND MATHEMATICAL

MODELING A QUADCOPTER AS AN OBJECT

MANAGEMENT

This chapter discusses the aerodynamic features of a quadcopter as an automatic control object. The purpose of aerodynamic analysis is to determine the power circuit of a quadcopter, assign a measure of reference for movement in space and develop a model of quadrocopter dynamics using differential equations, as well as in the formation of the laws of autonomous flight of a quadrocopter.

This chapter focuses on quadrocopter modeling issues and can be considered both linear and non-linear depending on the assumptions. The world trend in this direction tends to represent the quadcopter as a non-linear object. This approach is more realistic. In this regard, we propose a nonlinear model of a quadrocopter taking into account the shift of the center of gravity from its ideal geometric position, which coincides with the position of the center of mass.

Aerodynamic and mathematical analysis 2.1.

description of a quadrocopter as a control object and a description of its flight modes In space, a quadrocopter has six degrees of freedom, and its motion is described by six differential equations (Euler's equations). The solution of these equations in the general case would make it possible to determine the nature of the spatial motion of the quadrocopter at any moment of time and, in particular, to judge the stability of this motion.

However, the direct solution of these equations presents certain difficulties even with the use of modern computers. If, for the initial flight mode, we take a straight-line steady flight without slip and consider the deviations of the motion parameters from the initial values ​​to be quite small, then due to the symmetry of the quadcopter, the system of six equations of motion can be divided into two independent systems of equations with an unknown degree of accuracy that describe the motion of the quadcopter in the plane of symmetry (the so-called longitudinal movement) and in two other planes (lateral movement).

To quantitatively describe the position and motion of a quadrocopter in space, a variety of coordinate systems are used: inertial, terrestrial and mobile. The choice of one or another coordinate system is usually determined by the problem being solved.

Fixed or normal terrestrial coordinate system z z z. Its origin lies on the surface of the earth and the axes are fixed in relation to it. The z z axis is directed upward along the local vertical, i.e. in a straight line coinciding with the direction of gravity. The h and z axes lie in the local horizontal plane, forming a right-handed rectangular Cartesian coordinate system. The direction of the axes h and z is selected in accordance with the task.

A connected or movable coordinate system k k k k. This coordinate system coincides with the axes of the quadcopter body. Its origin k lies in the center of mass of the quadcopter, and the axes k to k are rotated by the roll, pitch and yaw angles from the axes of the fixed coordinate system z z z, as shown in Fig. 2.1. The longitudinal axis k k is located in the plane of symmetry

Figure 2.1 Coordinate and reference system of the quadcopter position

quadrocopter and is directed from the tail to the nose. The normal axis OkYk is located in the plane of symmetry of the quadcopter and is directed upwards. The transverse axis OкZк is perpendicular to the plane of symmetry of the quadcopter.

The roll angle is the angle between the transverse kk axis and the 3h axis of the normal coordinate system, shifted to a position at which the yaw angle is zero. The roll angle is positive if the displaced h z axis is aligned with the transverse axis by turning clockwise around the longitudinal axis when viewed in the direction of this axis.

to k Pitch angle is the angle between the longitudinal axis and the horizontal plane from the normal coordinate system. It should be considered positive if the longitudinal axis is above the horizontal plane from h.

The yaw angle is the angle between the axis from the normal coordinate system and the projection of the longitudinal axis to the horizontal plane from the normal coordinate system. The yaw angle is positive if the z z axis is aligned with the projection of the longitudinal axis on the horizontal plane by turning clockwise around the z z axis when looking in the direction of this axis.

The translational motion of a quadrocopter as a rigid body in space is the motion of its center of mass relative to the Earth.

The direction of the axes of the parameters of the quadcopter position of the moving coordinate system, the origin of which is located at the center of mass of the quadcopter, is selected in accordance with the task at hand. The spatial position of the quadrocopter during its translational motion relative to the Earth is fully described by three parameters: latitude (F), longitude (L) and altitude (H).

In addition to the translational motion, the quadrocopter also performs a rotational motion relative to the ground, which is a motion around its center of mass.

- & nbsp– & nbsp–

Therefore, with the help of RX, RY and RZ it is possible to determine the movements of the quadcopter in relation to the ground at any given time. This helps to monitor the correct operation of the on-board measurement systems of the miniature aircraft.

The quadcopter can only fly in four modes: roll, pitch, yaw and overhang. Using the laws of aerodynamics, it is possible to compose generalized equations of motion, which serve to describe the mathematical model of a quadcopter flight. Aerodynamic design is based on two theories: the theory of moments and the theory of design and action of the blades. The theory of moments models the rotor as an ideal drive, represented as an infinitely thin disc, the rotation of which produces a constant speed along the axis of rotation without regard to friction. All aerodynamic forces and moments acting on the rotor are determined using the theory of the action of the blades. We present an aerodynamic model of a quadrocopter with the assumption of the following factors: disk thickness is infinitely small;

the vertical air velocity is constant around the rotor; air is an ideal incompressible gas; rotors are rigid, the force parallel to the rotor shaft is defined as the rotor thrust T, and the force perpendicular to the rotor axis is defined as the hub force Tc. The acting moments on the rotor are braking MT and movable MT moments.

Since the calculation is performed without taking into account friction, it can be assumed that the lifting force acting on the blade is about an order of magnitude higher than the resistance force. In fig. 2.2 clearly visible all the painted aerodynamic forces and moments.

Figure 2.2 Aerodynamic forces and moments acting on the rotor Quadrocopters are modeled as a combination of four rotors operating on the principle of transverse configuration.

A rather thin and light cruciform frame connects mechanical motors (which are heavier than the frame). Each propeller (propeller) is connected to the motor through gearboxes. All axes of rotation of the screws are rigidly fixed and parallel. In addition, they have a fixed pitch of rotation of the blades, the air flow of which is directed downward to obtain the direction of the lift force upward. Motors and gearboxes are not fundamental factors in the flight of a quadcopter because movement is directly related only to the rotational speeds of the propellers.

The secondary mechanical component is the gearbox, in the sense that it doesn't play a significant role in understanding how a quadcopter flies. However, all of these components will be discussed later in the description of reactive control.

To assess the motion of a quadcopter, consider the basic model, which consists only of a light cruciform support structure with four screws installed at its ends. The front (rotor 1) and rear (rotor 3) screws rotate counterclockwise, while the left (rotor 2) and right (rotor 4) rotate clockwise. This twin counter-rotating configuration eliminates the need for a tail rotor such as in the case of a conventional helicopter. In fig. 2.3 shows the sketches of the structure of the quadcopter.

The angular velocities of each of the screws are indicated by an index corresponding to the serial number of the rotor. In addition to variable speed for each propeller, the up arrow represents the speed vector and will always point up. Hence, the rule of the right hand (clockwise rotation) should not be adopted, since the rotor also represents the vertical thrust vector.

- & nbsp– & nbsp–

Figure 2.3 Simplified speed diagram of a quadrocopter According to the model shown in Fig.

2.3, all propellers rotate at the same speed i [rad s-1], this causes a counterbalance to the acceleration of gravity in the aftermath when the quadcopter performs the hovering process. Thus, the quadcopter is in stationary mode, as there is no force or moment to move it from its current position.

Despite the fact that the quadcopter has six degrees of freedom, it is equipped with only four propellers, therefore, it will be difficult to achieve the desired state for all degrees of freedom. All states can be mathematically considered and modeled, however, in reality, the control system controls four states associated with four basic movements that allow the quadcopter to reach a specific height and position. It rises or falls depending on the speed value. Let's represent the mathematical model of the overhang mode using the expression:

4 (2.2) 1 = (+). (), =1

- & nbsp– & nbsp–

Figure 2.5 Pitch mode Yaw mode is achieved by increasing (or decreasing) the front and rear rotor speeds, or by decreasing or increasing the left and right rotor speeds, which creates a torque in relation to the height axis OZ.

Consequently, the quadcopter will rotate in relation to the OZ axis. The yaw motion is created by turning the left and right screws clockwise while the front and rear screws turn counterclockwise. Therefore, when the total torque is unbalanced, the aircraft turns around the OZ. Figure 2.6 shows the yaw mode.

- & nbsp– & nbsp–

Equation (2.27) can be used to construct a functional diagram of the pitch axis contour. It includes rotary motion about the roll axis () and translational motion (x). The functional diagram of the roll circuit is shown in Fig. 2.7.

- & nbsp– & nbsp–

The functional diagrams obtained as a result of the analysis of the quadrocopter (Fig. 2.72.10) represent the complete structure of the quadrocopter.

Representation of a quadcopter with a shifted center of gravity as 2.3.

nonlinear object and its mathematical modeling Flying robots are often classified by size and weight, such as micro-flying vehicles (MLA), they have a maximum size of 15 cm and their maximum weight is about 150 g.

Unmanned aerial vehicles of the miniature class have a minimum size of up to one meter and a maximum weight of 1 kg.

As has been shown, the apparatus can be controlled by four degrees of freedom directly by changing the rotation speed of the motors. Thus, the quadrocopter belongs to a special class of nonlinear controllable systems, since the control of six degrees of freedom is carried out only through 4 control inputs.

Today, the requirements in the field of autonomous flight of aircraft are constantly growing, they include high dynamics and maneuverability at low speeds, the ability to track targets, and nonlinearity of the solution. There are also requirements for the optimality and reliability of a real-time state control system that provides global stability.

It should be noted right away that the currently most common method of linear control is unacceptable for a quadrocopter, due to its nonlinearity as a control object.

In addition to the control task, to ensure flight autonomy, it is necessary to consider the issues of trajectory planning and navigation. To address navigation successfully, it should be recalled that all inertial navigation systems suffer from drift integration, as errors in feedback sensor signals gradually integrate into speed and position deviations. These errors can be compensated for by additional communications from high-precision sensors such as GPS, radar or laser scanner. However, the main problem with any indoor navigation concept is that an external navigation system such as GPS is not considered reliable or always available.

The problem of offline localization can be subdivided into two subtasks. One of them is the global localization of the quadcopter, i.e. position assessment without any a priori knowledge of one's position and orientation in the map. The second task is to track the trajectory using sensors (gyroscope, accelerometer), which leads to a result with an error. Based on this, to solve the issue of autonomous localization, it is necessary to group all the information coming from local sensors (gyroscope, accelerometer), auxiliary sensors, radar or laser scanner) to determine its own (GPS, location or flight orientation.

Due to the limitations of the payload for the quadcopter, only small and lightweight sensors can be used as ancillary means. Therefore, when calculating the sensor model, all degrees of freedom must be considered. The state space of a quadcopter is six-dimensional, which makes such a common approach as, for example, Monte Carlo very difficult to apply in localization problems, since the solution grows exponentially with the dimension of the state space. It can be assumed that real-time computation is not possible.

The main focus of this paper is on the unstable and non-linear behavior of the quadcopter. It is obvious that the effect of the displacement of the center of gravity (CG) from the ideal position is important in such systems. For example, attaching a battery or payload sensors, as well as lifting or dropping payloads, will shift the CG and disable the developed controllers for the original system with the original CG. Due to the shifted CG, inertial sensors perceive additional accelerations and speeds, which affects the final position of the quadcopter in a fixed coordinate system.

The generally accepted approach to quadcopter modeling is based only on ideal models with an ideal center of gravity.

Since one degree of freedom can be controlled by one control loop, the uncontrolled degrees of freedom are controlled using inertial and gyroscopic forces. A shift in the center of gravity changes the components of the moment of inertia with respect to a fixed coordinate system, which, in turn, leads to a change in the values ​​of the Euler angles. The new value of the moment of inertia depends on the distance by which the center of gravity has moved. It can be calculated using the following expression:

2 = 1 +. ct, (2.36) where 2 is the new value of the moment of inertia in relation to the center of measurement of states; 1 old value of the moment of inertia in relation to the center of gravity, the mass of the quadcopter; ct is the distance from the ideal to the real center of gravity.

To analyze the effect of changing the distance on flight conditions, we change the value of ct from 0.1 to 10%. To do this, we take a linear model of the quadcopter (see equations in the control system section). In fig. 2.11 shows the new position of the center of gravity.

- & nbsp– & nbsp–

As can be seen from Fig. 2.12, the system of automatic control of the states of flight of the quadcopter did not have time to track the desired trajectory along the pitch and roll axes.

Since the calculation of the regulator coefficients is carried out taking into account the ideal position of the center of gravity, control sensors transmit inaccurate information in the feedback signals. The deviation can reach large values, as can be seen from the simulation result, up to 20% (at 10% of the shear distance). This confirms the importance of taking into account the real position of the center of gravity when simulating a quadrocopter.

Figure 2.12 Simulation results for different values ​​of ct The concept of jet flight control of a quadcopter in 2.

unknown environment As discussed earlier, a quadrocopter, like other rotary-wing aircraft, has a single flight mechanism.

The combination of rotation of the rotors produces a change in pressure around the structure, therefore, the quadcopter rises or moves around the pitch, roll and yaw axes only in accordance with the resulting total thrust. Let's represent a non-linear model of a quadcopter using the Newton-Euler equation. The formulas describing the motion of the quadcopter are presented in a linked coordinate system due to the fact that the inertia of the quadcopter is not a function of time. Therefore, the kinematics of a rigid body with 6 degrees of freedom in a bound coordinate system can be described using the following equation:

- & nbsp– & nbsp–

- & nbsp– & nbsp–

- & nbsp– & nbsp–

З [0] = = = =,

- & nbsp– & nbsp–

() = [ 4) (1) ] = ;

(K = 1 = 1 + 2 3 + 4, where the vector of the rotation speed of all rotors, rad s-1; the rotation speed of the propellers, rad s-1; the matrix of the gyroscopic effect of the propeller, H m s-2.

Accordingly, from an aerodynamic point of view, moments and forces are directly proportional to the square of the propeller speed.

Consequently, the matrix of motion of the DC is also proportional to the square of the vector. Then you can calculate the vector of motion K () using the following equation:

(1 + 2 + 3 2 + 4 2) K () = DK 2 = =, (2 2 4 2) (2.46) (3 2 1 2) [(2 + 2 2 2)]

- & nbsp– & nbsp–

From here you can find expressions for the components of the vector:

1 = (1 2 + 2 2 + 3 2 + 4 2);

4 = (2 2 + 4 2 3 2 1 2).

- & nbsp– & nbsp–

The generalized acceleration vector of the quadcopter Г can be found using equations (2.50) and (2.51):

- & nbsp– & nbsp–

1 (2.53) = + () ;

- & nbsp– & nbsp–

After determining the laws of dynamics and connections between the components of the quadcopter, you can get the structure of the quadcopter flight control system. It consists of the following blocks:

- trajectory generator - flight missions. It can be stored in the ROM of the microprocessor system if the scheduling is global, otherwise it is generated during the flight depending on the local scheduling algorithm;

- external control loop. This is the quadcopter position control loop. It includes translational controls along the roll, pitch and yaw axis. The block output is a signal for the formation of Euler angles;

- middle control loop. This is a control loop for Euler angles, that is, rotational movements around the roll, pitch and yaw axes.

Determination of the values ​​of these angles is necessary to regulate the speed of rotation of the propellers and obtain the desired flight mode;

- the lower control loop. The purpose of this unit is to directly stabilize the quadcopter by varying the propeller rotation speeds.

Figure 2.15 Functional diagram of the flight control system of a quadcopter based on the principle of reactive control

- & nbsp– & nbsp–

In this chapter, a quadrocopter was considered as an object of automatic control.

1. Based on the analysis of its aerodynamic features, it was found that a quadrocopter with six degrees of freedom has only four flight modes: roll, pitch, yaw and overhang. The obtained mathematical models of flight modes were used to determine the linear model of the quadrocopter.

2. Aerodynamic and force analysis showed that there is a need to take into account the nonlinearities of the quadcopter for a more realistic representation of the automatic control object.

3. The factor of influence of the shift of the center of gravity of the quadrocopter from its ideal geometric position on its positioning was considered.

Analysis of the deviation from the desired trajectory showed that, without taking into account the shift factor, it is possible to admit an error in positioning along the roll and pitch axis within 120% in proportion to the shift value by 10%.

4. A nonlinear model of a quadrocopter is proposed, taking into account the shift of the center of gravity and gyroscopic effects in the laws of motion of the quadrocopter.

Force analysis showed that for flight control it is necessary to adjust the propeller rotation speeds in accordance with the generated flight mode. At the same time, the laws of jet flight control of a quadcopter were synthesized and a functional diagram of the control loops was drawn up.

CHAPTER 3. DEVELOPMENT OF A QUADROCOPTER FLIGHT TRAJECTORY PLANNING SYSTEM

Trajectory planning is a key theoretical and practical issue for the implementation of autonomous flight of a quadcopter.

In the previous chapters, the quadrocopter was simulated, the forces and moments acting on the body were determined, in addition, the equations of motion of the quadrocopter in space were obtained. Now let's look at how to use these equations to implement autonomous flight.

As noted in the first chapter, flight planning needs to be viewed from two perspectives: locally and globally, so as to simulate the actual action of the pilot. Based on the results of the second chapter, the application of the center of gravity shift factor in the mathematical model of the quadcopter was justified. This made it possible to develop in more detail the concept of implementing an autonomous flight and achieving optimal positioning of the quadrocopter without auxiliary navigation systems.

Naturally, the description of the global part of the planning algorithm precedes the local part, since the global algorithm is responsible for the general view of the flight, that is, determining the start and end of the flight, taking into account that the environment is known. To do this, we divide the structure of the chapter into two main parts. In the first part, we will consider the global planning of the trajectory of a quadrocopter in a known environment using the A-star search algorithm, analyze its advantages and disadvantages. On the basis of the results obtained, in the first part, a new planning algorithm is proposed, which is superior in efficiency to the optimized A-star algorithm. The goal of the algorithm is to be able to implement real-time trajectory planning using the available computing power. At the same time, the cost of new resources will remain unchanged.

Development of a hybrid global search algorithm 3.1.

planning the flight path of a quadcopter based on the A-star algorithm and the potential fields method The global algorithm should consider methods for avoiding known obstacles. This is done using an optimized trajectory planning search algorithm.

To generate the trajectory, the A-star or A * algorithm is adopted. Search algorithms have also been used in various trajectory generation examples. They are fast acting and easy to implement. However, their huge disadvantage is the problem of local minimum. Once in this position, the robot will not be able to make a decision for further movement. In the case of unmanned vehicles, the task is more serious than that of ground robots. The UAV can remain in hover mode until it runs out of power. In the case of a quadcopter, this is the battery. For miniature aircraft, the battery can withstand no more than 15 minutes. It follows from this that the problem of a local minimum is a dangerous situation for aircraft, since there is a risk of an accident.

Much research has been devoted to solving this problem. In this work, the method of potential fields is used to solve the local minimum problem.

A-star is a best-first-match search algorithm on a graph that finds the least-time-consuming route from one vertex (start) to another (target). The order of traversing the vertices is determined by a heuristic function, which is calculated by summing the distance + time spent. This function f (x) is the sum of two others: the time cost function g (x) of reaching the considered vertex (x) from the starting point of motion and a heuristic estimate of the distance h (x) from the considered vertex to the final one. Expression (3.1) describes the method for finding the heuristic function:

() = () + (). (3.1) The function h (x) must be a valid heuristic estimate, that is, it must not overestimate the distance to the target vertex. For example, for a routing problem, h (x) might represent the distance to a target in a straight line, since this is the physically smallest possible distance between two points.

The A-star algorithm is a type of network search for planning the path of robotic systems, since it considers space as a 2D configuration and breaks it down into geometric one-dimensional shapes.

Therefore, we can say that the algorithm does not recognize the elements of space and does not determine which configuration to set up - 2D or 3D.

To use the algorithm correctly, you need a GPS system or save the map in the autopilot memory. Consequently, the A-star algorithm works only in static spaces, where the location of objects and obstacles does not change during the planning of the trajectory and movement.

Let us formulate the motion planning problem for a miniature flying robot - a quadcopter. It must fly from point S (start) to point G (target) with a constant flight altitude Zconst without colliding with objects on the 2D path. The algorithm must also solve the local minimum problem in the event of a collision. After planning a safe, optimal flight path, it is necessary to set the obtained coordinates at the input of the autopilot and solve the inverse problem of dynamics in order to carry out the movement. Let's start with the space of motion. The flight map is shown in Fig. 3.1.

- & nbsp– & nbsp–

If we assume that all the squares are one-dimensional and the side length of the square is 10, then we get that the movement is carried out from the center of point S to the center of the next point. Therefore, the value of the function g (x) takes the following values:

() = 10 if the movement is orthogonal;

() = 14 if the movement is diagonal.

Now let's determine the distance between each of the border cells to the target G, taking into account that the distance is calculated only orthogonally. As an example, let's say that the distance from point S3 to point G is equal to 4 cells (Fig. 3.3), therefore, we can find the values ​​of the function h (x) using the following formula:

(3.2) () = 10 ·, where K is the number of cells that orthogonally separate any cells (for example, S3) from the target (G).

- & nbsp– & nbsp–

After finding the value of the function f (x), the quadcopter should move to the cell with the smallest value of the function f (x). Therefore, the quadcopter must move to cell S5, but before that the navigation system will take the next step:

1. The cells around S5 are determined.

2. The values ​​of the function g (x) are saved.

- & nbsp– & nbsp–

- & nbsp– & nbsp–

- & nbsp– & nbsp–

Using the algorithm for finding and optimizing the quadcopter's route, we find the coordinates along the OX and OY axes along which the quadcopter should fly. As can be seen from Fig. 3.7, the coordinates change abruptly, which is an extreme case of quadrocopter control.

The results of simulating control of a quadrocopter are shown in Fig. 3.8.

- & nbsp– & nbsp–

Optimized using the method of potential fields, the A-star algorithm made it possible to implement trajectory planning in a known environment, taking into account known obstacles, and this was carried out avoiding the problem of a local minimum.

However, the optimized A-star algorithm has a number of disadvantages that must be taken into account before recommending it for use in trajectory planning. First, the performance of the algorithm is directly related to the size of the map or known flight environment. If the problem of a local minimum arises in flight, then one has to consider the potentials of all cells. Secondly, if the algorithm is used without auxiliary navigation systems, then the coordinates of the obstacle will need to be determined on the spot in real time.

To do this, it is necessary to install sensors on board a quadrocopter with a limited carrying capacity. In parallel, it is necessary to increase data processing resources. Therefore, it is recommended to use the optimized A-star algorithm when planning the flight path of a quadrocopter connected to navigation systems, so as to avoid the need to place additional sensors on it.

Trajectory planning using optical odometry 3.2.

At this stage, a universal algorithm for planning and generating a trajectory using a vision system is considered, based on a geometric approach that links various coordinate reference systems. At the same time, the laws of transitions from the pixel coordinate system to the hybrid frame of reference are formulated, obtained in the second chapter. The proposed algorithm can be used as a local and global trajectory generator without auxiliary navigation systems and in real-time flight mode.

3.2.1. Global Trajectory Planning Algorithm The task of global planning is to fly to control points. This approach has already been applied in determining the position of the quadcopter and controlling the altitude using the color of the static label. The difference between the proposed algorithm and the well-known methods of controlling a quadrocopter using a vision system is that for autonomous localization, the autopilot of the quadcopter determines the distance traveled by calculating the number of rotors' revolutions and the side of rotation, that is, it finds the relationship between the pixel system and the associated coordinate reference system. In this case, the question arises as to the peculiarities of localization in the concept of flight autonomy: how does a quadrocopter, a miniature flying robot, determine how far to move it? Usually, information from the global localization system and onboard sensors is used to determine the location of an aircraft, in this case a quadrocopter. Here it is proposed to solve the problem with the help of a technical vision system and the method of optical odometry, which makes it possible to determine the location and orientation of movement based on the sequence of optical information (images) in each time step. Let's consider the concept of optical odometry in accordance with three reference systems (Fig. 3.9):

fixed or Terrestrial coordinate system in which the real flight path is calculated;

associated coordinate system or frame of reference in relation to the quadcopter;

frame of reference by the position of the camera, fixed at a certain angle in relation to the axes of the quadcopter. The pixels of the camera serve as the coordinate axes OfXfYf.

Figure 3.9 Coordinate reference systems for the problem of autonomous flight To change the position of the quadcopter in relation to the Earth, using the camera frames, it is necessary to find geometric relationships between different coordinate reference systems.

Quadrocopter AR DRONE is an object that has diagonal aperture deviations within 64 degrees. Using the laws of trigonometry (Fig. 3.9), we obtain the angles of vertical and horizontal deviations equal to 43.18 degrees and 51.62 degrees, respectively.

Radio engineering, including television systems and devices DISSERTATION for the degree of candidate of technical sciences Scientific adviser Doctor of technical sciences ... "MARIA SERGEEVNA GRIDINA STUDY OF THE INFLUENCE OF OIL-CONTAINING WASTE COMPONENTS ON THE QUALITY OF HYDRAULIC WASTE PRODUCTS. Chemical Sciences Supervisor: Candidate of Chemical Sciences ... "

"Al-Jaberi Ramzi Hamid Improving the efficiency of protection of corporate telecommunication computer networks in Yemen in conditions of low certainty. Specialty 05.12.13 - Systems, networks and devices ..."

"SHMYREV Denis Viktorovich IMPROVEMENT OF CONTAINER TRANSPORTATION OF CHOPPED WOOD BY WATER TRANSPORT 05.21.01 -" Technology and machines for logging and forestry "DISSERTATION for the degree of candidate of technical sciences.

"Gorbunov Sergey Andreevich JUSTIFICATION OF PARAMETERS AND DEVELOPMENT OF HIGHLY LOADED, ADAPTIVE, RADIAL VORTEX DIRECT FLOW FANS FOR LOCAL VENTILATION Specialty 05.05.06 -" Ekaterinburg Machines "Thesis for the degree of candidate of technical sciences Makarov 5 Analysis of the state, problems and criteria ... "

«Baga Vadim Nikolaevich UDC 621.5.02 + 621.22– IMPROVEMENT OF METHODS FOR CALCULATION AND DESIGN OF LABYRINTH SEALS OF PNEUMATIC UNITS SHAFT BASED ON MODELING OF THE WORKING PROCESS 05.05.17 - Hydraulic machines and hydraulic machines for the scientific degree of the scientific degree of the candidate Andrei German tech. sciences, professor Sumy - 201 CONTENT ... "

“Zavgorodniy Dmitry Anatolyevich FAMILY VALUES AND ORIENTATIONS OF RUSSIAN YOUTH IN THE CONDITIONS OF DEMOGRAPHIC CRISIS: INFLUENCE FACTORS AND DEVELOPMENT TRENDS 22.00.04 - social structure, social institutions and processes Dissertation for the degree of candidate of professional sciences. ... S.I. Samygin Krasnodar - 2014 Contents Introduction..3 Chapter 1 .... "

«ROMANIUK MARGARITA IGOREVNA THEORETICAL BASES FOR CALCULATION OF ULTRASONIC TRACKS OF METAL ROLLED SURFACE CONTROL DEVICES Specialty 05.09.08 - Applied acoustics and sound engineering DISSERTATION for the degree of candidate of technical sciences, Professor Petri INTRODUCTION SECTION ... "

PYLAEVA Ekaterina Mikhailovna ACTUALIZATION OF THE KEY CONCEPTS OF THE TRANSLATION TEXT: ECOLINGUISTIC APPROACH (based on the novel by A. Ivanov "The Geographer Drank the Globe on Drink" and its translation into French) Specialty 10.02.20 - Comparative-historical, typological and comparative linguistics Thesis for competition candidate of philological sciences ... "

"KHOKHLOV Dmitry Yuryevich IMPROVEMENT OF TECHNOLOGIES AND MEANS OF ENSURING THE UNINTERRUPTED POWER SUPPLY OF THE AGROINDUSTRIAL COMPLEX Specialty: 05.20.02 - Electrotechnology and electrical equipment in agriculture"

"DORONINA Olga Ivanovna INFORMATION-MEASURING SYSTEM FOR MONITORING THE RELIABILITY OF AIR POWER LINES Specialty 05.11.16 -" Information-measuring and control systems (in mechanical engineering) "DISSERTATION for the degree of candidate of technical sciences Scientific adviser: Doctor of Technical Sciences ..."

"Mohammed Kamil Ali Gazi POWER PLANT FOR HEAT SUPPLY TO CONSUMERS USING SOLAR HEATERS IN THE CLIMATIC CONDITIONS OF IRAQ Specialty: 05.14.01 -" Power systems and ... "

"Mikhaylov Viktor Alekseevich DEVELOPMENT OF METHODS AND MODELS OF ANALYSIS AND ESTIMATION OF STABLE FUNCTIONING OF ON-BOARD DIGITAL COMPUTER COMPUTERS UNDER THE CONDITIONS OF INTENTIONAL EXPOSURE OF A DOCTOR OF ULTRA VELOCITY of a telecommunication system. ... "


2016 www.site - "Free electronic library - Abstracts, dissertations, conferences"

The materials on this site are posted for review, all rights belong to their authors.
If you do not agree that your material is posted on this site, please write to us, we will delete it within 1-2 business days.

This article is rather a logical continuation of my article about the balancer: "Creating a balancer robot on arduino."
It will very briefly highlight: a simple model of angular stabilization of a quadcopter using quaternions, linearization, building control for an object and checking it in Matlab Simulink, as well as checking on a real object. The test subject will be Crazyflie 1.0.

Now it flies like this (at the time of filming, I did not set the controls very correctly):

Building a dynamic system

Let's introduce 2 coordinate systems: local, linked to the ground, and the second, linked to the copter.

The rotation of a body is more convenient to represent using quaternions, due to the less amount of computation required. Many articles have been written about them, including on Habré. I recommend reading the book “VN Branets, IP Shmyglevsky. Applying Quaternions in Orientation Problems ”, thanks to Slovak from the MathWorks Competency Center for the tip.

Let's use the basic law of the dynamics of rotational motion:

Where
- moments acting on the body,
I is the tensor of inertia, and
- angular velocities along the main axes (in a linked coordinate system).
Thus:
.

By virtue of the theorem on the reduction of the tensor of inertia to the principal axes, we represent the tensor of inertia in the form: .

External moments are defined through controls:, where

Thus, the equations of angular velocities in a coupled coordinate system:

Note that if we took into account the position of the copter, it would be possible not to introduce separate control functions, but immediately use traction forces as them, which is more convenient and faster in calculations. In this case, the stabilization system does not have any data on the required amount of traction forces, therefore it is necessary to use just such controls ...

Propeller thrust can be roughly described as. Then the equations can be written in terms of the angular frequencies of the propellers, if you can control the frequency of the motors directly and know the specific b:
where
- euler angles
Note that the selection of the coefficient b for me was made manually, by simple selection.

It is also necessary to write down the equation for the rotation quaternion. It follows from the properties of quaternions that
, where are the angular velocities in the coordinate system associated with the aircraft, in which the gyroscopes measure the angular velocity.

Let's try to stabilize only angles and angular velocities:

Or more

Let us introduce the vector of the state space:
.
It should be noted that if a component enters the vector of space, the system ceases to be controllable. However, we can assume that we also remove it from the state vector, thereby reducing the number of coordinates.

Control vector:
,

The system is presented in a standard form

In our case

, but

Linearization and control building

Linearizing the system near the origin, we obtain the following matrices A and B:

,

Like last time, we use a linear-quadratic controller. Let me remind you the Matlab command for calculating it:
= lqr (A, B, Q, R)
The matrices Q and R are weight matrices. Q penalizes deviation from zero, and R penalizes control power consumption.
As a result, we got the matrix K. In my matrix of coefficients, all the off-diagonal elements were very small (of the order of 10 ^ -4) and I did not take them into account.
Let me remind you that in order to obtain control, it is necessary to multiply the matrix K by the vector X. Of course, in the code you can omit the concept of a matrix and simply multiply each coordinate by some factor for performance.

Model check

To check the results obtained, a model was created in Matlab Simulink. Let's start it with nonzero initial conditions.

The first graph shows how the angular velocities behave, the second - the change in the components of the quaternion. Note that the scalar value of the quaternion comes to one, even though it does not appear in the equations of the linearized system. As you can see from the graphs, the model is stabilizing.

Code

Crazyflie uses the Free RTOS system, where all the code is divided into modules, we are interested in the sensfusion6.c and stabilizer.c code.
Fortunately, the filtering of the accelerometer and gyroscope readings is done in quaternions, the problem is that the sensors on the drone are positioned for the + circuit. I calculated the model for the X scheme. The only difference is in the choice of controls U1 and U2.

You need to add the code for getting the quaternion to sensfusion6.c:

Void sensfusion6GetQuaternion (float * rq0, float * rq1, float * rq2, float * rq3) (* rq0 = q0; * rq1 = q1; * rq2 = q2; * rq3 = q3;)

I didn't add a separate module for the LQR regulator, instead I changed stabilizer.c. Yes, perhaps this is not the most intelligent way, but it will work for checking the model.

It is worth starting by adding variables for the current and desired position of the apparatus, as well as controls:

Static float q0Actual; static float q1Actual; static float q2Actual; static float q3Actual; static float q1Desired; static float q2Desired; static float q3Desired; int16_t actuatorU1; int16_t actuatorU2; int16_t actuatorU3;

We do not indicate the desired position in q0 due to the fact that we do not need to stabilize it.

Let's make changes to the command receiving code. The copter receives the angle in degrees, mathematically, it is more correct to do this:

CommanderGetRPY (& q1Desired, & q2Desired, & q3Desired); q1Desired = cos ((- q1Desired / 2 + 90) * 0.01745); // * 3.14 / 180/2; q2Desired = cos ((q2Desired / 2 + 90) * 0.01745); q3Desired = cos ((q3Desired / 2 + 90) * 0.01745);

Let's change the "fast" cycle (250Hz) of the stabilizer:

Sensfusion6UpdateQ (gyro.x, gyro.y, gyro.z, acc.x, acc.y, acc.z, FUSION_UPDATE_DT); sensfusion6GetEulerRPY (& eulerRollActual, & eulerPitchActual, & eulerYawActual); sensfusion6GetQuaternion (& q0Actual, & q1Actual, & q2Actual, & q3Actual); sensfusion6UpdateP (FUSION_UPDATE_DT); sensfusion6UpdateV (acc.x, acc.y, acc.z, FUSION_UPDATE_DT); actuatorU1 = 50 * (1 * (- gyro.x) + 245 * (q1Actual-q1Desired)); actuatorU2 = 50 * (1 * (gyro.y) -200 * (q2Actual-q2Desired)); actuatorU3 = 50 * (1.5 * (gyro.z) + 0 * (q3Actual-q3Desired));
The selection of the coefficients was made empirically, since it was not possible to find out the relationship between the command sent to the motors and the power that the motor unit produces.

I also changed the power distribution function of the motors:
static void distributePower (const uint16_t thrust, const int16_t u2, const int16_t u3, const int16_t u4) (motorPowerM1 = limitThrust ((thrust / 4 + u3 / 2 + u4 / 4) * 5); motorPowerM2 = limitThrust ((thrust / 4 -u2 / 2-u4 / 4) * 5); motorPowerM3 = limitThrust ((thrust / 4-u3 / 2 + u4 / 4) * 5); motorPowerM4 = limitThrust ((thrust / 4 + u2 / 2-u4 / 4 ) * 5); motorsSetRatio (MOTOR_M1, motorPowerM1); motorsSetRatio (MOTOR_M2, motorPowerM2); motorsSetRatio (MOTOR_M3, motorPowerM3); motorsSetRatio (MOTOR_M4, motorPowerM4);)

Conclusion

Based on the fact that the copter stabilizes its angles, we can conclude that the mathematical model has been developed correctly. Unfortunately, it is not yet possible to get your coordinates and speeds (integrating the accelerometer gives a huge error), so the copter does not suppress the initial speed and does not return to the initial position.
To solve this problem, MIT, for example, uses cameras and tags on its copters.

In the practical use of the equations of motion of UAVs, they are written in projections on the axes of the selected coordinate systems (SC). In this work, it is convenient to use two right-handed rectangular coordinate systems, let's call them fixed and moving coordinate systems:

1. Fixed coordinate system. Start to be at point O, at which you need to stabilize the quadcopter. The OX and OY axes are located in the horizontal plane, and the OZ axis is directed upwards.

2. Moving coordinate system. Start to be in the center of mass of the quadcopter, at the point. The axes of this coordinate system:, and are co-directed with the coordinate axes of the stationary CS. Thus, a movable SC is obtained from a stationary SC by parallel transfer to the radius of the vector of the center of mass of the quadcopter in a stationary SC.

Rice. 1.2.

Moment of inertia

Let the quadcopter lie in the OXY plane, its center of mass is at point O, and the beams AC and BD, on which the rotors are located, lie along the OX and OY axes. The moment of inertia of the quadcopter is the same around any axis MN lying in the plane of the quadcopter OXY. Let's denote the mass of the quadcopter as. Let the mass of each rotor be concentrated at points A, B, C and D and equal, and the entire mass of the body is uniformly distributed on the segments AC and BD and equal.

Rice. 1.3.

Then the moment of inertia of the quadcopter relative to any axis MN component with the axis BD angle b is equal to:


The moment of inertia about the OZ axis, perpendicular to the OXY plane and passing through the point O, is calculated by the formula:

Equations of motion

A quadrocopter, like any rigid body, is a system with six degrees of freedom, therefore, to describe its motion, six independent numerical equations or two vector equations are required.

Equations of motion of the center of mass

The gravity vector is applied to the center of mass of the quadcopter and has the form:, where is the gravitational acceleration.

Air resistance force, where - dimensionless aerodynamic coefficient, - air density, - surface area. Thus, the force of air resistance is proportional to the square of the speed with a certain coefficient and is directed opposite to the speed.

The vector of the total thrust force of all rotors is also applied to the center of mass and has the form:, where, and are the thrust forces of the first, second, third and fourth rotors, respectively

The vector of some extraneous force will be denoted as. In the case when the force is caused by the wind, since the force with which the wind acts on the quadcopter is actually the force of air resistance.

Thus, the vector equation describing the motion of the cent of the masses of the quadcopter in a fixed coordinate system has the form:

Velocity can be obtained by expressing acceleration and integrating it over time:

By integrating the speed, the radius vector to the center of mass of the quadcopter is obtained, i.e. coordinates of the position of the center of mass of the quadcopter:

Equation of moments:

The equation of moments in this case is convenient to consider relative to the center of mass, in a moving coordinate system. The equation of moments describes the rotation of a body about an instantaneous axis. In this model, rotation can only be caused by the forces that the rotors create. Let us introduce vectors

And are the radius vectors of the rotors in the moving coordinate system. The lengths of these vectors are equal to each other and are equal.

Rice. 1.4.

In this case, it is more convenient to split this equation into two: the first equation will describe the rotation around the axis of symmetry of the quadcopter, the second equation will describe the rotation around the axis lying in the plane of the quadcopter. Then the first equation is:

Expressing the angular acceleration from this equation and integrating it over time, you can get the angular velocity:

where, and в are the components of the vector along the coordinate axes.

By integrating the angular velocity over time, it is possible to obtain the angles of rotation of the quadcopter around the axes of the moving SC:

where the components, and vectors are the angles of rotation around the axes of the normal coordinate system OX, OY and OZ, respectively.

Consider the rotation of a quadrocopter around an axis perpendicular to the plane. Let's designate the reactive moment of the screws as. The vector of this depends only on the magnitude and is directed along the normal to the plane of the quadcopter. In addition to the reactive moment, there is also a moment of forces co-directed to it, caused by the gyroscopic effect due to a change in the gyroscopic moments of the rotors, which can also rotate the body of the quadrocopter around this axis, but since the rotors rotate in different directions, it can be ignored. Then the modulus of angular acceleration is expressed by the formula:

Where is some function depending on the value.

By integrating this expression, you can get the angular velocity module, while the obtained angular velocity will always be directed perpendicular to the plane of the quadcopter. Let's denote the unit vector directed perpendicular to the plane of the quadcopter as. Thus, we get:

And by integrating this equation, we obtain the angles of rotation of the quadcopter around the axes of the moving SC.

Thus, the total values ​​of the angular velocity and angles of rotation will be equal to:

news of the wounds. theory and control systems, 2013, no. 6, p. 114-121

MOVING OBJECT CONTROL SYSTEMS

udk 681.5.075

STABILIZATION OF THE PROGRAM MOTION OF THE QUADROCOPTER *

F. Yu.Baklanov and V. M. Morozov

Moscow, Research Institute of Mechanics, Moscow State University Received April 24, 2013, in revision June 28, 2013

The problem of constructing a control law for a quadrocopter - a four-rotor helicopter is considered. The classical design of such an apparatus is a cruciform frame, at the tops of which there are installed electric motors with propellers rigidly fixed on their axes. An approach to solving the problem is proposed, based on the application of the two-level control method, according to which the required control is constructed as a sum of program control and additional feedback that stabilizes the zero solution of the system of equations in deviations from the programmed motion. The complete controllability of the non-stationary linear system of equations in deviations is rigorously proved. To construct a stabilizing feedback, a well-known solution to the problem of a linear controller with a quadratic performance criterion is used. The proposed approach makes it possible to develop a general numerical method for constructing a control that ensures stable motion of a quadrocopter along arbitrary smooth three-dimensional trajectories.

B01: 10.7868 / 80002338813060036

Introduction. Among the wide variety of small-sized unmanned aerial vehicles, a special class should be distinguished - quadrocopters. The classical design of such an apparatus is a cross-shaped frame, at the tops of which electric motors are installed, on the rotors of which the main screws are rigidly fixed. Electric motors are installed in such a way that the axes of rotation of their rotors are perpendicular to the plane of the frame. The main difference between a quadrocopter and an ordinary helicopter is the absence of propeller swashplate in its design. The movement of the quadcopter in the plane of the horizon is achieved by tilting the entire vehicle as a whole, and not by changing the orientation of the rotors relative to the body. Thus, the construction of a quadcopter is simpler than that of an ordinary helicopter and provides greater maneuverability.

At the moment, there are several dozen works in which the problem of constructing control algorithms for a quadrocopter is considered. Nevertheless, all existing works, even the most complete and detailed ones, have at least one of the following disadvantages:

only software stabilization of the orientation and flight altitude of the quadcopter is considered, and the movement in the horizon plane is not taken into account,

to construct a control algorithm, an assumption is made about the smallness of the orientation angles of the quadcopter, and a linear stationary model of motion is used,

the study of the complete controllability of the constructed mathematical model of the quadrocopter and the theoretical study of the stability of the obtained control algorithm are not carried out.

The paper presents the most complete study of the dynamics of quadcopters at the moment, including the construction of a nonlinear mathematical model that takes into account the aerodynamic air resistance, the study of the controllability of a dynamic system, the construction of a control algorithm that ensures stable motion along arbitrary smooth trajectories in three-dimensional space, as well as rigorous proof of motion stability.

1. Statement of the problem. It is believed that a quadrocopter (see Fig. 1) is an absolutely rigid axisymmetric body. To determine the position of the quadrocopter, an absolute inertial coordinate system Oxxy is introduced with the origin at an arbitrary point on the Earth's surface, the z axis of which is directed vertically upward, and the x and y axes lie in the horizon plane so that the unit vectors

* This work was supported by the Russian Foundation for Basic Research (grants No. 12-01-00800 and 12-01-00371).

Rice. 1. Quadrocopter model

axes x, y, I form a right-hand triplet, and a movable coordinate system O2, nC, rigidly connected with the quadcopter, with the origin at the center of mass O, the axes of which are directed along the main central axes of inertia. The tensor of inertia in these axes has the form / = diag (A, A, C). The quadcopter is affected by gravity, air drag force ¥ dt &, thrust forces of engines B and moments of engines M, i = 1.4. The thrust forces of the engines are variable in modulus, but always co-directional with the axis of the OS, the moving coordinate system. It is believed that the force of air resistance is determined by the ratio ¥ dt & = -kpS \ VIV, where V is the velocity vector of the center of mass, k is the dimensionless drag coefficient, B is the characteristic area, p is the air density. Aerodynamic moments acting on the quadcopter frame are not taken into account.

The position of the quadcopter is determined by the coordinates x, y, z of the center of mass in the absolute coordinate system and the Euler-Krylov angles a, p, y, which specify the orientation of the quadcopter. The transition from the O1xy1 coordinate system to the O2, nC coordinate system is carried out using three rotations: the O1xy1 → Ox1y111 transition - by turning about the O1x axis by the roll angle a, the Ox1y111 → Ox2y2¿2 transition - by turning relative to Oy2 by the pitch angle p, the Ox2y2¿2 transition ^ О2, пС - by turning relative to Oz2 by the course angle y. Then the matrix of the transition from the coordinate system Oxxy to the system O ^ nC has the form

cos р cos у cos а sin у + sin а sin р cos у sin а sin у- cos а sin р cos у - cos р sin у cos а cos у- sin а sin р sin у sin а cos у + cos а sin p sin y sin p - sin a cos p cos a cos p y

The absolute angular velocity of the quadcopter in projections on the axis of the moving coordinate system has the form

^ a cos p cos y + | 3 sin y ^ -a cos p sin y + P cos y a sin P + p

To write the equations of motion of a quadrocopter, theorems are used on the motion of the center of mass and on the change in the angular momentum relative to the center of mass

mv = F, J + [, J] = MO.

Here m is the mass of the quadrocopter, B is the main vector of external forces, MO is the main moment of external forces relative to the center of mass.

F = ^ F + mg + Fdrag, Mo = ^ momoFi + momoFw + Mrot, i = 1 i = 1

where momOFi, momOFw are the moments relative to the center of mass of the thrust forces of the engines and the force of gravity, respectively, g is the vector of acceleration of the force of gravity,

The moments Mi are perpendicular to the plane O ^ n, and M1 and M3 give a positive projection onto the OS axis, and the moments M2 and M4 are negative.

The components of the traction forces ^, having components (0,0, p) m in the moving coordinate system, in the absolute coordinate system are defined as the corresponding components of the vectors

BT (0,0, p) T- We introduce the designation | VI = ^ x2 + y2 + v.2. Then the components of the air resistance force can be written as

(Fdrag) x = -cr £ X | V, (P ^) y = -cr $ \ VI, (¥ ara & = -crB1 \ V.

The moments of forces p relative to the point O are determined by the expressions

momOF1 = -aFen, momOF2 = -aF2e ^, momOF3 = aF3en, momOF4 = aF4e ^.

Here d ^ u are the unit vectors of the О2 and Оц axes, respectively, and a is the distance between the center of mass of the quad-rocopter and the attachment points of the engines. The moments of gravity relative to the center of mass are zero.

According to experiments carried out at the Institute of Mechanics of Moscow State University, there is a relationship

Fi = cru, and M1 = km, where ω are the angular velocities of the propellers, cr and km are some constants. therefore

where i (0 = 1 at, = 1.2, n (-) = 0 at, = 3.4, kMP = kM / cr.

U1 "F1 (0 -a 0 a \

u2 = Q ■ F2, Q = -a 0 a 0

u3 F3 kMF -kMF kMF -kMF

U4 J 1F4 j 1 1 1 1 1)

Equations (1.2) in scalar form are written in the form

A cos p cos ya + A sin yp + (A - C) cos p sin p sin yá + + (-2A + C) sin p cos yá p - C cos p sin yá y + C cos yp y = ub

A cos p sin ycx + A cos yp + (A - C) cos p cos y sin pá -

- (-2A + C) sin p sin ycx p - C cos p cos ycxy - C sin yp y = u2, C (sin pa + y + cos pá y) = u3, mx = U4 sin p + (Fdrag) x ,

my = -U4 sin a cos p + (Fdmg) y,

mz = u4 cos a cos p + (Fdrag) z - mg.

The aim of the work is to determine the control actions required to ensure the movement of the center of mass of the quadcopter along a given smooth trajectory in three-dimensional space and with a certain programmed heading angle.

2. Building a control system. To construct a control law that ensures a given programmed motion of system (1.5), we use the method of two-level control

niya, in which the control action is formed as a sum of program and positional controls.

The peculiarity of the problem is that to specify the entire vector of generalized coordinates of the system

(x, y, z, a, p, y) as a programmed motion is impossible, since the number of control actions (four) is less than the number of generalized coordinates. In addition, the design of the quadcopter is such that, for example, to implement a programmed movement in the horizontal plane, it is necessary to provide some non-zero roll and pitch angles that allow this movement to be realized. Therefore, the programmed motion of the quadcopter will be specified by four smooth functions of time xd (t), yd (t), zd (t), Yd (t) - the position of the center of mass of the quadrocopter and the heading angle.

To determine the programmed controls u4, j = 1.4, and the programmed values ​​of the roll and pitch angles, we use equations (1.5). We have

A cos p¿ cos yda¿ + A sin y¿ (3¿ + (A - C) cos p¿ sin p¿ sin y¿а2d + + (-dA + C) sin pd cos yda dp d - C cos p¿ sin y ¿a ¿Y d + С cos y ¿в d Y d = Щ,

Cos pd sin y d a d + A cos y ¿p d + (A - C) cos p¿ cos y d sin p¿ ad -

- (-dA + C) sin pd sin Y d "dp d - C cos pd cos Y d" dY d - C sin Y dp dY d = udd, (21)

C (sin pd a d + Y d + cos pd “dY d) = u3d. X d = U 4 sin pd -Kv ¿X d,

yd = -U4d sin a d cos pd - K v dY d,

z.d = u<4d cos ad cos pd - KVdZ¿ - mg.

Here u = u¿ / m, k = kpS / m, vd = yjx] + yd + ¿d. The last three of equations (2.1) serve to determine the values ​​of ad, pd, and u:

tan a d _- * + KV¿yd, "¿d + KVdZd + g

tan pd = - (x d + Kvd-x d) cos a d, (2.2)

For further reading of the article, you must purchase the full text. Articles are sent in the format PDF to the mail indicated when paying. Delivery time is less than 10 minutes... Cost of one article - 150 rubles.

Similar scientific works on the topic "Cybernetics"

  • STABILIZATION OF TRANSLATIVE-ROTARY MOTION OF A SINGLE-AXIS WHEEL PLATFORM ON A STRAIGHT-LINE TRAJECTORY

    SACHKOV G.P., FESHCHENKO S.V., CHERNOMORSKY A.I. - 2010

  • ROTOR-WINGED MACHINES DESIGNER

    TISHCHENKO MARAT - 2009

  • STABILIZATION OF HELICOPTER MOVEMENT IN ALL VARIABLES

    A. A. Shevlyakov - 2014

  • TO THE SELECTION OF THE TYPE OF DRIVE OF THE POWER UNIT OF THE MECHATRONIC SYSTEM

    G. V. Kreinin, S. Yu. Misyurin - 2015

3d scanner. Lidar zenmuse l1 https://artdrone.ru/catalog/dji-podvesy/354/ from DJI.