Open access peer-reviewed chapter

Quadrotor Unmanned Aerial Vehicles: Visual Interface for Simulation and Control Development

Written By

Manuel A. Rendón

Submitted: 05 December 2020 Reviewed: 26 March 2021 Published: 27 May 2021

DOI: 10.5772/intechopen.97435

From the Edited Volume

Robotics Software Design and Engineering

Edited by Alejandro Rafael Garcia Ramirez and Augusto Loureiro da Costa

Chapter metrics overview

478 Chapter Downloads

View Full Metrics

Abstract

Quadrotor control is an exciting research area. Despite last years developments, some aspects demand a deeper analysis: How a quadrotor operates in challenging trajectories, how to define trajectory limits, or how changing physical characteristics of the device affects the performance. A visual interface development platform is a valuable tool to support this effort, and one of these tools is briefly described in this Chapter. The quadrotor model uses Newton-Euler equations with Euler angles, and considers the effect of air drag and propellers’ speed dynamics, as well as measurement noise and limits for propeller speeds. The tool is able to test any device just by setting a few parameters. A three-dimensional optimal trajectory defined by a set of waypoints and corresponding times, is calculated with the help of a Minimum Snap Trajectory planning algorithm. Small Angle Control, Desired Thrust Vector (DTV) Control and Geometric Tracking Control are the available strategies in the tool for quadrotor attitude and trajectory following control. The control gains are calculated using Particle Swarm Optimization. Root Mean Square (RMS) error and Basin of Attraction are employed for validation. The tool allows to choose the control strategy by visual evaluation on a graphical user interface (GUI), or analyzing the numerical results. The tool is modular and open to other control strategies, and is available in GitHub.

Keywords

  • Quadrotor
  • Trajectory Planning
  • Trajectory Tracking

1. Introduction

Quadrotors are a special type of unmanned aerial vehicles (UAVs), increasingly employed last years for mapping, surveillance, searching and tracking operations, in rescue missions, agriculture, traffic management, landscape film making, and others [1, 2, 3].

When quadrotors applications demand large angle attitude control and obstacle avoidance, the following areas still need to be strengthened: Aggressive maneuvering control, visual-based control, localization in indoor environments, optimizing the computational cost for complex algorithms, and fault-tolerant disturbance rejection [4]. Several controllers have been proposed for these tasks: classic techniques as PD [5] and PID [6], optimal techniques as LQR [7] and LQG [8], non-linear techniques such as Lyapunov [9] and Backstepping [5, 9] and intelligent and adaptive control techniques as Fuzzy200 [10] and Reinforcement Learning [11].

Research in quadrotor demand sophisticated equipment and costly laboratory. However, it can be optimized employing low cost virtual development tools. In autonomous control the path planning, path tracking and joint operation with other UAVs, can be supported by optimization techniques with support of software tools [1, 2, 12]. Published works relate the use of software such as Visual Basic, MatLab, Panda3D, Gazebo, or more open applications developed in languages as Python and C++ [2]. In [1], a UAV 3D flight environment programmed in Python and developed in Panda3D is presented. A GUI developed in LabVIEW was published in [2], and other developed on MatLab-Simulink employs quadratic linear regulator (LQR) control [13].

Gazebo is an important virtual environment for robotics. Its integration with ROS provides a powerful testbed to analyze control algorithms. In [12] works that employ Gazebo and ROS for developing simulation of UAVs are described.

Most of the cited simulation tools have a difficult start for users with little programming experience. Even open-source models can be tricky. An interesting tool depicted in [14, 15] gives support for quadrotor control development, analyzing and comparing various control strategies on challenging trajectories. It may be used by beginning users with not much knowledge in ROS, Gazebo or in programming languages such as Python or C ++. The tool easies the understanding of quadrotor dynamics and related equations, as well as the development of control strategies. The present Chapter describes this user-friendly framework, the employed techniques are described in [14, 15, 16, 17].

Section 2 presents a description of the employed model. Section 3 explains the optimal trajectory planning method. Section 4 describes the controllers available in the tool. Section 5 presents the graphical user interface developed by the tool. Section 6 presents the graphical and numerical results. In the end of the Chapter, the Section 7 emphasizes the main aspects and critical issues related.

Advertisement

2. Quadrotor model

The equations are described in the rigid body model of the quadrotor, and its displacement is related to an inertial frame, fixed on the Earth surface [18]. Three main frames are considered for a quadrotor model: Inertial (I), Vehicle (V) and Rigid Body (B), as illustrated in Figure 1.

Figure 1.

Main frames in a quadrotor.

The quadrotor owns 4 propellers in cross configuration. Each pair of propellers (1,3) and (2,4) rotates in opposite directions (Figure 1). Setting different rotor speeds to each pair (ω2ω4) or (ω1ω3) produces roll or pitch rotations with corresponding lateral motion. Yaw rotation results from rolling moments difference (M1+M3M2M4) between propellers [9]. Maximum and minimum motor speeds are some of the parameters to be set in the model.

Newton-Euler equations describe quadrotor dynamics and kinematics [9, 18]. The Rotation Matrix represents the rotation around the three axes in the sequence ZXY (1), and is described in (2).

RBZXYI=RA2IψRA1A2ϕRBA1θE1
RBZXYI=Δcψcθsϕsψsθcϕsψcψsθ+cθsϕsψcθsψ+cψsϕsθcϕcψsψsθcθsϕcψcϕsθcϕcθE2

The angle ϕ around the x axis is the roll angle, the angle θ around the y axis is pitch angle, and the ψ angle around the z axis is yaw angle.

The orientation vector is defined by η and the position of quadrotor’s center of mass is defined in the reference frame I by r. Angular velocities in the body frame B (p, q and r) are defined by ν (3).

η=ϕθψr=xyzν=pqrE3

The derivative of the angles ϕ, θ and ψ and the angular velocities measured by a sensor fixed to the Frame of the Rigid Body are not the same. p, q and r are the angular velocities around the x, y and z axes of the Rigid Body Frame. The relationship with the angular rates ϕ̇, θ̇ and ψ̇ in the same frameB is in (4).

pqr=Tϕ̇θ̇ψ̇=0cϕsθ010cϕcθϕ̇θ̇ψ̇E4

Considering that the body is symmetrical with respect to the x-z and y-z planes of the frameB,and that the only forces acting on it are the weight and the four thrusts, its resulting linear acceleration with respect to the inertial Frame can be described using Newton’s Second Law. Air drag forces are represented by a matrix in (5), and the values of Ax, Ay and Az, are inputs on the parameters set.

mr¨I=00mgI+RBI00FiAx000Ay000AzBE5

Besides the force each rotor produces a moment in the rigid body perpendicular to the plane of rotation of the propeller (Mi), contrary to the direction of rotation of the propellers. L is the size of the quadrotor arm (Figure 1) and J the inertia matrix presented in (6).

J=Jxx000Jyy000JzzE6

Due to the forces produced by the rotors, moments are produced in the rigid body (LFi), causing the system to rotate around the x and y axes. The rotation around the z axis is due to the torque created by the rotation of the motors, which are fixed to the plant. Based on the Coriolis Equation, the equation that describes the angular acceleration in the FrameB is in (7).

Jṗq̇ṙB=LF2F4LF1F3M1+M2+M3+M4BpqrB×JpqrBE7

For simulating the measurement noise, the tool allows to add a random signal to position and orientation variables and their derivatives. A first order delay between the comands u1 and u2 and rotor speed variations, with a time constant τ seconds, was included in the tool to simulate the rotor dynamics.

Advertisement

3. Trajectory planning for a set of waypoints

Due to the low inertia of quadrotor it is necessary to calculate a smooth trajectory to minimize the risk of collapse. Euler–Lagrange equations are used to find the minimum snap trajectory [15, 19]. For a two waypoints trajectory, the boundary conditions of position, velocity, acceleration, and jerk are defined in Table 1.

Time tPosition xdestVelocity ẋdestAcceleration x¨destJerk x¨dest
0xdes0000
TxdesT000

Table 1.

Boundary conditions.

With this boundary conditions the equations’ coefficients for the two-points optimal desired trajectory are calculated for each coordinate of position (xdes, ydes and zdes) and orientation (ψdes) (8).

xdesydeszdesψdes=c1,7c1,6c1,5c1,4c1,3c1,2c1,1c1,0c2,7c2,6c2,5c2,4c2,3c2,2c2,1c2,0c3,7c3,6c3,5c3,4c3,3c3,2c3,1c3,0c4,7c4,6c4,5c4,4c4,3c4,2c4,1c4,0t7t6t5t4t3t2t1E8

Desired angles for roll (ϕdes) and pitch (θdes) are calculated from ψdes, the equations depend on which control strategy is employed.

This procedure yields a minimum snap trajectory for two points. For additional waypoints it is necessary to consider more equations and intermediary restrictions [15].

The tool calculates the complete optimized trajectory for any set of waypoints. Desired trajectory rdes, orientation ψdes, and their derivatives are calculated for being used in the control algorithms.

Advertisement

4. Attitude and trajectory following control strategies

Some of the challenges to be overcome in quadrotor operation are: attitude stability for large angles, trajectory following, collision avoidance through aggressive maneuvers, monitoring, and others [2, 4].

The control architecture employed in the following control strategies uses two cascaded loops. The inner loop (attitude control) runs in a fast time-scale and is assumed exponentially stable. The outer loop (position control) runs in a slow time-scale, with a higher bandwidth [4]. All of them employ a feed-forward with proportional plus derivative structure (FF-PD). The tool is open to easily add more control strategies.

4.1 Small angle control

Small Angle control assumes an operation not too far from the hovering condition. A simple heuristic method with FF-PD control calculates the required accelerations for the desired trajectory (9).

x¨cy¨cz¨c=rdes+Kper+KderE9

It is assumed small deviations from zero in roll and pitch angles, small deviations in the yaw angle from the desired value, and angular velocities close to zero. The algorithm assumes all upward-pointing thrust vectors (control signal u1 in (10)).

u1=mg+z¨cE10

After linear simplifications the equations for attitude control are defined in (11) and (12) [16].

ηc=ϕcθcψc=1gx¨csinψdesy¨ccosψdes1gx¨ccosψdes+y¨csinψdesψdesE11
νc=pcqcrc=TηcE12

A PD control law is used for attitude control and to calculate u2 (13) [16].

u2=KRηcη+KννcνE13

4.2 Desired thrust vector control

At high speeds and roll and pitch angles far away from zero, a more robust strategy is necessary. A FF-PD control law calculates the control signal u1 for the trajectory following and compensates the gravity. Vector t is calculated with the attitude for the desired effect (14). As u1 acts along the z direction in frame B (axis bz), it must be referred to frame I (15).

t=mrdes+Kper+Kder+mgazE14
u1=tTRbzE15

The axis bz is desired to be aligned with t. The desired rotation matrix Rdes is calculated from the equation of rotation of bz in the direction of t (16).

Rdesbz=ttE16

As we know ψdes we use (16) to calculate ϕdes and θdes. Rdes is constructed with these three angles with the same structure of (2). The error in rotation ΔR is calculated from (17).

ΔR=RBITRdesE17

With the Rodrigues formula [20], the axis of rotation v and the rotation angle β are calculated (18). I3×3 is the identity matrix and v̂ is the skew-symmetric matrix of v (19). The related error is calculated with (20).

ΔR=I3×3cosβ+vvT1cosβ+v̂sinβE18
v̂=0v3v2v30v1v2v10E19
eR=βvE20

A PD control law is used to calculated u2 (22).

eν=νcνE21
u2=ν×Jν+JKReRKνeνE22

Basin of attraction Ψ limits the set of rotations from which the quadrotor is able to converge to the hovering state. It is a dimension of the set of angular and linear velocities for a stable performance. For this control strategy it must be lower than 2 (23).

Ψ=trI3×3RdesTRBI<2E23

4.3 Geometric tracking control

Geometric Tracking Control exhibits almost global exponential attractiveness to the zero equilibrium of tracking errors [17]. t and u1 are calculated as in (14) and (15). bx is the desired direction vector in the first body-fixed axis (24).

bx=cosψdessinψdes0E24

With t and bx is possible to calculate Rdes with (25) to (27) [17].

bz=ttE25
by=bz×bxbz×bxE26
Rdes=by×bzbybzE27

(27) calculates the desired attitude for the quadrotor given t and ψdes. The basin of attraction Ψ (28) is bigger than in the previous strategy (23) as this is a more robust approach [17].

Ψ=12trI3×3RdesTRBI<2E28

Attitude tracking error and angular velocity error are calculated from (29, 30). The control vector u2 is calculated in (31) [17].

eR=12RdesTRBIRBITRdesE29
eν=νRBITRdesνdesE30
u2=ν×Jν+JKReRKνeνJν̂RBITRdesνdesRBITRdesν̇desE31

4.4 Particle swarm optimization for control gains tuning

A PSO algorithm is employed to tune the control gains. Some adjustments were performed to reduce the processing [14, 15], s. Each particle αi is a vector with the proportional and derivative gains (32).

αi=KpKdKRKνE32

Using a predefined set of waypoints chosen by the user, the code calculates the desired trajectory and tests each particle, calculating the RMS error. The PSO algorithm evolves in the direction of the best validated solution in each iteration, until achieving a minimum error tolerance. For faster convergence, every time a particle is evaluated, the evaluation is interrupted in the middle of the trajectory if the error increases above a predefined limit.

Advertisement

5. The graphical user interface

A user-friendly 3D animated GUI was developed in MatLab. It is able to evaluate and compare the performance of various quadrotor control strategies for any user-chosen trajectory. A few of quadrotor parameters are easily set in this interface [15].

A red vertical line indicates the upper side of the device, and a red circle the front rotor. Waypoints are represented by red markers, the desired trajectory is on dashed blue line, and the 3D interface axis limits are automatically adjusted from the waypoints (Figure 2).

Figure 2.

Graphical user interface.

Waypoints, quadrotor parameters and simulation comands are set in th buttons on the left side of the GUI.

The user may test its own control strategy just by creating the corresponding code like the following example:function New_Controller% declare global variablesglobal quad;% holds the quadrotor in the last waypointif(quad.iteracao > length(quad.rdes(1,:)))Controlador_Position_Hold()end% start the controller code and calculate the global control commandsquad.u1=...quad.u2=...

The code New_Controller.m must be stored in the folder Controllers, and will be recognized in the dropdown menu in the lower left side of Figure 2.

Advertisement

6. Results

The tool developed in MatLab and is available in GitHub [21]. The values employed for these results are in Table 2 [3].

For simulating the measurement noise, a random signal was added to position (±0.01m) and orientation (±0.5) variables and their derivatives. Maximum and minimum motor speeds make the simulation more reliable. A time constant τ of 0.1 s for dynamic rotor speed variation was considered.

Two sets of waypoints of challenging trajectories were tested, each one was simulated in three different initial conditions: Case 1 starting with an orientation angle of ϕ0=0, Case 2 with ϕ0=88, and Case 3 with ϕ0=178. The three control strategies available in the tool were graphically and numerically validated.

6.1 Elliptical helix trajectory

The first trajectory waypoints (Table 3) describe an elliptical helix in a forward trajectory along with the x axis of inertial frame ix.

ParameterValueUnits
Jxx4.856×103kg.m2
Jyy4.856×103kg.m2
Jzz8.801×103kg.m2
k2.980×106N.s2/rad2
g9.81m/s2
m0.468kg
Ax0.25kg/s
Ay0.25kg/s
Az0.25kg/s
b1.100×107N.m.s2/rad2
L0.225m
Nimax8500rpm
Nimin1300rpm
τ0.1s

Table 2.

Quadrotor parameters [3].

tsxdesmydesmzdesmψdesrad
0.00−0.400.002.000.00
1.200.000.002.000.00
1.800.200.002.600.00
2.400.400.402.001.57
3.000.600.001.403.14
3.600.80−0.402.004.71
4.201.000.002.606.28
4.801.200.402.007.85
5.401.400.001.409.42
6.001.60−0.402.0011.00
6.601.800.002.6012.57
7.201.800.002.6012.57

Table 3.

Waypoints test 1.

With this set it was calculated the desired optimal trajectory. Using this trajectory the PSO algorithm calculates the optimal gains for each of the three evaluated control algorithms.

With this gains the simulation was performed and validation errors in each of the four coordinates were registered. Tables 46 present the gains used in each case, and corresponding validation errors.

Control StrategyKpKdKRKνxv%yv%zv%ψv%
Small Angle17.967.110.2310.161.3737.7636.3011.0300
DTV18.9110.7744.92023.432.1124.9075.3000.6455
Geometric Tracking7.347.3590.59020.753.1728.80726.6800.3973

Table 4.

Elliptical helix trajectory case 1, ϕ0=0.

Control StrategyKpKdKRKνxv%yv%zv%ψv%
Small Angle22.762.000.7650.1972.0132.6926.220.6344
DTV19.704.85155.40026.7101.5822.0327.650.4949
Geometric Tracking8.245.62220.20027.6703.1735.9451.570.4027

Table 5.

Elliptical helix trajectory case 2, ϕ0=88.

Control StrategyKpKdKRKνxv%yv%zv%ψv%
Small Angle8.1802.3492.450.43715.98864.98146.11.223
DTV7.2683.434236.4031.43004.70933.71105.41.351
Geometric Tracking

Table 6.

Elliptical helix trajectory case 3, ϕ0=178.

When calculating the gains using PSO it was observed that the processing time increases substantially with the initial orientation angle (ϕ0). It was also observed in cases 2 and 3 that once a set of optimal gains is calculated, later results do not reduce substantially the validation error.

Small angle control is more sensible to variations in rotational positions as observed in the results. Optimal small angle control gains are bigger than rotational (Tables 46). The opposite occurs for DTV and geometric tracking.

Case 3 is the most challenging since the quadrotor starts almost upside down. Geometric tracking controller is more sensitive to noise error, PSO did not succeed in finding a set of gains in Case 3.

A visual validation is possible using the tool. Graphics in Figure 3 show the performance of small angle control in Case 3. The quadrotor drops and recoverers the vertical position, and continues along with the desired trajectory. Graphics on the right supports a visual validation of position and orientation variables.

Figure 3.

Elliptical helix trajectory case 3 small angle control, ϕ0=178.

In the graphics of propellers’ speeds of Figure 4, dashed red lines indicate the speed extremes. In extreme situations, the controller attains the propellers’ limits.

Figure 4.

Propellers’ speeds in rpm with small angle control.

Figure 5 presents the performance of DTV Control on Case 3. It is observed a faster reaction and a more accurate trajectory following.

Figure 5.

Elliptical Helix Trajectory Case 3 DTV Control, ϕ0=178.

Near the third point the trajectory leads the quadrotor to its limits. Propellers’ speeds in Figure 6 show a more stable performance than the previous strategy.

Figure 6.

Propellers’ speeds in rpm with DTV control.

Compared with small angle, this strategy seems to be more robust and accurate.

Figure 7 presents the performance of geometric tracking control in Case 2. This strategy reacts faster to challenging situations, since it recovers in a shorter time its hovering orientation. This fast reaction makes it more sensitive to measuring noise.

Figure 7.

Elliptical helix trajectory case 2 geometric tracking, ϕ0=88.

Figure 8.

Propellers’ speeds in rpm with geometric tracking.

Propellers’ speeds in Figure 8 confirm the faster command reaction of the controller compared with Figures 4 and 6. This strategy is also sensitive to nonlinear behaviour. When it reaches the propeller limits, it is highly prone to instability.

The gains calculated for the more challenging Cases were later tested on Cases 1 and 2. Despite being less optimal they displayed a stable behaviour. The performance is presented in Table 7.

Control Strategyϕ0xv%yv%zv%ψv%
Small Angle1.3737.7636.3011.0300
Small Angle13.11121.96028.3900.2430
Small Angle88°2.01032.69026.2200.6344
Small Angle188°3.24251.76049.5800.3378
DTV2.1124.9075.3000.6455
DTV14.62515.65013.3100.2350
DTV88°1.58422.03027.6500.4949
DTV188°4.88641.58044.5300.3509
Geometric Tracking3.1728.80726.6800.3973
Geometric Tracking23.3385.91728.6600.2615

Table 7.

Validation comparison for cases 1 and 2.

1 Calculated with Gains of Case 3.

2 Calculated with Gains of Case 2.

Graphical results of small angle control performance on Case 1, when using the optimal gains compared with the performance with the gains calculated for Case 3. The system holds the attitude performance. The same comparison was performed for DTV control. The decrease in performance is lower than with the small angle controller [15].

6.2 Lemniscate Shape Trajectory

A second set of waypoints presented in Table 8, depicts a lemniscate shape trajectory varying the position in Z, orienting the front of quadrotor (yaw angle ϕ) in the direction of displacement.

tsxdesmydesmzdesmψdesrad
0.000.000.002.00−1.57
0.400.12−0.281.58−0.79
0.800.40−0.401.400.00
1.200.68−0.281.580.79
1.600.970.002.000.79
2.001.250.282.420.79
2.401.530.402.600.00
2.801.810.282.42−0.79
3.201.930.002.00−1.57
3.601.81−0.281.58−2.36
4.001.53−0.401.40−3.14
4.401.25−0.281.58−3.93
4.800.970.002.00−3.93
5.200.680.282.42−3.93
6.600.400.402.60−3.14
6.000.120.282.42−2.36
6.400.000.002.00−1.57

Table 8.

Waypoints test 2.

Figure 9 depicts the second trajectory.

Figure 9.

Lemniscate shape trajectory.

As with the to previous trajectory, the small angle control compensates its limitations with lower gains to guarantee stability, gains are bigger for position control than for attitude.

DTV Control is again the best validated strategy. Geometric tracking presents a lower performance due to its sensitivity to noise and nonlinear operation conditions. The DTV control had presented the best validation even in the most challenging conditions.

Detailed results and analysis of this trajectory are available in [15].

Using the tool the graphical and numerical analysis was easier. Not much programming knowledge was necessary for using and configuration, just basic MatLab programming. Access to quadrotor parameters of the analyzed device, analyzing the influence of measurements noise, and comparing and simulating different control strategies is easier than with other visual platforms. Graphical and numerical simulation results are easily available with the interface buttons.

Advertisement

7. Summary

Quadrotor control is a fascinating research area, but the equations involved and programming skills requirements can be arduous for initiating students. It is a worth to develop motivational appliances for beginners. This was the motivation to present a beginner-friendly visual interface tool for the development of quadrotor control strategies. It is easy to understand, device characteristics are simple to configure, and control algorithms can be implemented and analyzed with not much effort. It is not necessary to have a deep knowledge in programming languages, and may be an introduction to this field of research.

This tool uses RMS and basin of attraction for numerical validation, and the GUI may help to evaluate stability, robustness, and accuracy. It integrates these criteria in a unique interface and helps to measure and visualize details and requirements that may not be so clear using other visual tools.

Baseline controllers are offered so students may compare performance, and is open to easily introduce other strategies for comparison. A trajectory planning based on minimum snap give support to trajectory following control, and GUI allows the evaluation in dimensions of position and time.

The tool makes easier and faster to realize critical quadrotor requirements and limitations for challenging applications. These requirements may be related with the complexity of a defined trajectory, the weakness of a control strategy, or the improvements that may be carried out in the quadrotor (size, weight, propeller power, etc.) to accomplish the desired results.

Other controllers can be studied and compared using this tool, such as Backstepping and intelligent strategies. In the trajectory planning stage, applications with obstacles may be simulated. Support for multiple quadrotors, communication with the controller via Robotics Operating System (ROS) and implementation of obstacles are some of the future improvements planned for this tool.

Advertisement

Abbreviations

ROS
PSO
DTV
RMS
GUI
UAV
PD
PID
LQR
LQG
FF-PD
Advertisement

Nomenclature

I
V
B
ωi
Mi
Fi
ϕ
θ
ψ
ϕ̇
θ̇
ψ̇
sϕ,sθ,sψSine of angles ϕ, θ and ψ
cϕ,cθ,cψCosine of angles ϕ, θ and ψ
RXY
p
q
r
η
r
ν
T
L
J
x
y
z
er
er
Kp
Kd
m
g
KR
t
bi
I3x3
v
β
eR
Ψ
α
k
b
τ

References

  1. 1. Annaz F. Uav testbed training platform development using panda3d. Industrial Robot: An International Journal. 2015;42(5):450-456
  2. 2. A Zul Azfar and D Hazry. Simple gui design for monitoring of a remotely operated quadrotor unmanned aerial vehicle (uav). In 2011 IEEE 7th International Colloquium on Signal Processing and its Applications, pages 23–27. IEEE, 2011
  3. 3. A Tayebi and S McGilvray. Attitude stabilization of a four-rotor aerial robot. In Decision and Control, 2004. CDC. 43rd IEEE Conference on, volume 2, pages 1216–1221. IEEE, 2004
  4. 4. Tiago P Nascimento and Martin Saska. Position and attitude control of multi-rotor aerial vehicles: A survey. Annual Reviews in Control, 2019
  5. 5. Can Dikmen I, Arisoy A, Hakan Temeltas. Attitude control of a quadrotor. In Recent Advances in Space Technologies. RAST’09. In: 4th International Conference on, pages 722–727. IEEE. 2009. p. 2009
  6. 6. Gabriel M Hoffmann, Haomiao Huang, Steven L Waslander, and Claire J Tomlin. Quadrotor helicopter flight dynamics and control: Theory and experiment. In Proc. of the AIAA Guidance, Navigation, and Control Conference, volume 2, page 4, 2007
  7. 7. Domingues JMB. Quadrotor prototype. Dissertacio: Uneversidade Tecnica deLisboa; 2009
  8. 8. Ly Dat Minh and Cheolkeun Ha. Modeling and control of quadrotor mav using vision-based measurement. In Strategic Technology (IFOST), 2010 International Forum on, pages 70–75. IEEE, 2010
  9. 9. Samir Bouabdallah and Roland Siegwart. Backstepping and sliding-mode techniques applied to an indoor micro quadrotor. In Proceedings of the2005IEEE international conference on robotics and automation, pages 2247–2252. IEEE, 2005. ISBN 078038914X
  10. 10. C Nicol, CJB Macnab, and A Ramirez-Serrano. Robust neural network control of a quadrotor helicopter. In Electrical and Computer Engineering,2008. CCECE2008.Canadian Conference on, pages 001233–001238. IEEE, 2008
  11. 11. Steven Lake Waslander, Gabriel M Hoffmann, Jung Soon Jang, and Claire J Tomlin. Multi-agent quadrotor testbed control design: Integral sliding mode vs. reinforcement learning. In Intelligent Robots and Systems,2005.(IROS 2005).2005 IEEE/RSJ International Conference on, pages 3712–3717. IEEE, 2005
  12. 12. Fadri Furrer, Michael Burri, Markus Achtelik, and Roland Siegwart. Rotors—a modular gazebo mav simulator framework. In Robot Operating System (ROS), pages 595–625. Springer, 2016
  13. 13. Subhan Khan, Mujtaba Hussain Jaffery, Athar Hanif, and Muhammad Rizwan Asif. Teaching tool for a control systems laboratory using a quadrotor as a plant in matlab. IEEE Transactions on Education, 60(4): 249–256, 2017
  14. 14. Manuel A Rendón and Felipe F Martins. Unmanned quadrotor path following nonlinear control tuning using particle swarm optimization. In 2018Latin American Robotic Symposium, LARC 2018 and 2018 Workshop on Robotics in Education WRE 2018, pages 509–514. IEEE, 2018
  15. 15. Manuel A Rendón, Felipe F Martins, and Luis Gustavo Ganimi. A visual interface tool for development of quadrotor control strategies. Journal of Intelligent & Robotic Systems, pages 1–18, 2020
  16. 16. Mellinger D, Michael N, Kumar V. Trajectory generation and control for precise aggressive maneuvers with quadrotors. The International Journal of Robotics Research. 2012;31(5):664-674
  17. 17. Lee T, Leoky M, N Harris McClamroch. Geometric tracking control of a quadrotor uav on se (3). In Decision and Control (CDC). 49th IEEE Conference on, pages 5420–5425. IEEE. 2010;2010
  18. 18. Randal Beard. Quadrotor dynamics and control rev 0.1. Technical document, Brigham Young University, Provo, UT, USA, February 2008
  19. 19. Daniel Mellinger and Vijay Kumar. Minimum snap trajectory generation and control for quadrotors. In 2011IEEE International Conference on Robotics and Automation, pages 2520–2525. IEEE, 2011
  20. 20. Jian S Dai. Euler–Rodrigues formula variations, quaternion conjugation and intrinsic connections. Mechanism and Machine Theory, 92: 144–152, 2015
  21. 21. Felipe F. Martins and Manuel A. Rendón. Easyquadsim: Easy quadrotor simulator. GitHub, 2019. URL EasyQuadSim

Written By

Manuel A. Rendón

Submitted: 05 December 2020 Reviewed: 26 March 2021 Published: 27 May 2021