I Introduction
As autonomous unmanned aerial vehicles (UAVs) are being deployed in a wide area of real-world robotics applications [1, 2, 3, 4], there is a growing demand to broaden the scope of their applicability, effectiveness, and robustness. Due to this demand, improving a UAV’s agility and enabling aerial manipulation has received considerable interest. Advances in these areas may unlock deployment in numerous use-cases. For instance, drone-based inspection of bridges [5] may require the drone to collect measurements with a sensor that must remain in contact with the bridge structure at all time. This requires the drone to adapt its own orientation to the bridge’s geometry, while controlling its position independently. Enabling a drone to reach and hold any possible pose also gives rise to many further applications such as enabling uninterrupted complex camera motions for film shots [6]. These are only two of the many possible applications that would benefit from overcoming the limits imposed by the dynamics of most commercially available multi-rotor UAVs.
The demand and interest for novel UAV concepts has been mirrored by numerous research projects. In [7], a small Vertical Take-Off and Landing (VTOL) platform is proposed. The system begins its flight as a multi-copter, before transitioning into a fixed-wing mode for comparably long-endurance surveillance and inspection flights. Handling of strong winds for platforms of this size is investigated in [8]. This concept comes at the cost of a lower agility compared to a ”classical” multi-copter. The Omnicopter [9] can generate forces and torques in any direction. This is achieved by intelligent rotor placement in a cube-like structure. It has the downside of counteracting forces that can reduce the systems efficiency and hence its flight time and only a limited usefulness of certain rotors in a given configuration.
The use of tilting rotors promises to address some of the aforementioned challenges. A concept and simulation of a multi-copter involving tilting rotors was presented in [10] and experimentally evaluated in [11]. More approaches were evaluated in [12, 13]. While improving upon maneuverability, these approaches do not offer omnidirectional flight capabilities. The work in [14] also involved tilting rotors, but only considered two distinct flight modes, one in horizontal and one in vertical orientation. The concept presented in [15] is the most similar design we are aware of to the proposed Voliro platform. However, this work merely considered control of orientation and did not propose any approach for jointly controlling position and orientation. While the aforementioned works pushed the boundaries of multi-copter agility, they did not demonstrate omnidirectional flight over the whole flight envelope of a system with tilting rotors.

Our goal is to overcome the limitations of common commercially available multi-copters while preserving their advantages. The main conceptual challenge for achieving this goal is the mechanical design and control of the system. To achieve this the mechanical design is required to address three challenges: (1) Incorporating the hardware that enables additional maneuverability while providing a low weight; (2) Placing the propellers such that they can contribute to the system in any configuration and generate as little counteracting forces as possible; (3) Safe design such that a tool can be easily mounted and the drone operated close to a given surface. These three challenges also translate into challenges for designing the controller.
In this work, we present Voliro
, a hexacopter with tiltable rotors. As the rotor orientation can be fully controlled, this system allows for decoupling the control of position and orientation. It can be easily controlled through a PID controller and a simple allocation scheme which translates the control output into motor configurations. A prototype system is demonstrated and controlled in a large range of configurations while utilizing a Vicon system to provide state estimation. The contributions of this work can be summarized as follows:
-
The mechanical design of a fully-controllable hexacopter with tilting rotors.
-
The corresponding control and allocation schemes.
-
Evaluation of the concept in real-world experiments on a prototype platform.
Ii System Description
Ii-a Mechanical Design
The prototype presented in this work has six rotors arranged evenly on a circle (Figure 1) in a traditional helicopter configuration. These rotors arms are made of carbon fiber tubes and each rotor has the ability to rotate around the axis of the arm. Only the motor and its housing rotates. This rotation is achieved using brushless DC motors, which are inserted at the end of the arms, as can be seen in Figure 2. The arms themselves are rigidly attached to the platform main frame. This gives increased structural rigidity of the system when compared to designs that would rotate the entire arm.

The tilting motors are in diameter and are equipped with three Hall sensors and a high ratio gearbox for precise position estimation and control.
The tilting motors have a maximum rotation speed of and a maximum torque of . This allows for fast control of the tilting angles. The decision to use this motor setup over RC servo motors was made as such servos are typically limited to of rotation, which would limit the flight envelope of the platform. A further advantage of the brushless motors is their narrow profile which allowed them to be hidden inside the platforms tubular arms.
With this setup, the rotors are capable of rotating around their axes. The limiting factor in this design is the winding of the thrust motor cables around the arms.
Ii-B Hardware
This section introduces the main electronic and mechanical components of the system. For the generation of thrust 9 inch DJI propellers and KDE2315XF-885 motors were used. This propultion system is capable of providing a maximum of
of thrust per motor. The system requires a high thrust-to-weight ratio in order to be able to hover at large inclination angles, where most rotors cannot orient their force vector to directly oppose gravity. Faulhaber 1226S012B1 brushless DC motors were utilized in the rotor tilting system. Each of these tilting motors requires a motion controller which measures the current position of the motor shaft and applies the required voltage to control its position. To power the motors and the electronic components at different voltages, a 6-cell LiPo Battery and accompanying power distribution boards have been used. Table
3 shows the full list of electronic components on this platform.In order to house these electronics, a special core was designed using customized parts. The core is made out of two thick carbon fiber plates and assembled using aluminum screws. Aluminum spacers keep the plates a fixed distance apart to provide room for the electronics. They also act to clamp the carbon tubes on which the rotor units are mounted. Inside of the core are a Pixhawk flight controller, an UP Board embedded computer that provides additional computational power, and the motion control boards for the tilting motors.
The presented system has a total weight of and a flight time of around in its horizontal orientation. This flight time decreases significantly if the system is required to hover at a large inclination angle.
Component | Name |
---|---|
Thrust Motors | KDE2315XF-885 |
ESC | KDEXF-UAS35 |
Tilt Motor | 1226S012B1 |
Motion control board | MCBL 3002 |
Battery | Swaytronic LiPo 6S |
PDB | Piko PDB |
BEC 12 V | micro BEC |
BEC 5 V | Reely UBEC |
Onboard computer | UP Board |
Flight controller | Pixhawk |
RC receiver | Futaba R3008SB |
WiFi Antenna | Dlink DWA-172 5 GHz |
Ii-C Flight Controller
The Pixhawk flight controller used on this platform consists of an Inertial Measurement Unit (IMU), magnetometer, barometer, and a Cortex-M4F microprocessor. The Pixhawk runs the PX4 software [16], which handles full control of the multicopter as well as the interfaces with other devices. It also provides a flexible and modular framework that allows the integration of new control schemes.
Using the built-in state estimation provided by the PX4 software, the sensor data obtained by the IMU is fused together with the external pose information from a Vicon motion capture system or GNSS in the case of outdoor flight to provide an estimate for the system’s position. This information enters the controller block together with the desired pose trajectory which is generated by the user on an external computer. This desired trajectory is then sent to the UP board via Wifi, and ultimately to the Pixhawk through a serial connection. The controller block contains both the position and attitude controller, as well as an allocation block that maps the desired forces and moments onto the twelve actuators. This is crucial to the decoupling of position and orientation. After the desired control inputs are calculated, they are fed into the mixer block, which maps these values to the actuator PWM signals.

Iii Modelling
The development of a system model for such a vehicle is a necessary step in enabling model-based control synthesis and thorough testing. To fulfill this task a methodology that combines rigid-body dynamics with well established aerodynamic modeling techniques was used.
Iii-a Coordinates and Conventions
In this section the coordinate systems and notation conventions used are explained.
Iii-A1 Coordinate Frames
Overall eight coordinate frames were used. The inertial frame is fixed on the ground and its z-axis points upwards. In contrast, the z-axis of the body frame points downwards as seen in Figure 5. Its origin is at the center of gravity. And finally, there are the six coordinate frames of the rotor units shown in Figure 6. Their origins are at the center of the rotor blades and their x-axes are aligned with the axes to the center of mass of the body. Theses coordinate frames rotate around their x-axes with respect to the body frame.


Iii-A2 Notation convention
Throughout this paper we use left-hand subscripts for the coordinate system a symbol is referenced in. E.g. stands for a vector represented in coordinate system . The Matrix stands for the rotation matrix that rotates a vector represented in coordinate system to the coordinate system
The estimate of a state will be denoted with a hat on top of the symbol: .
Iii-B Assumptions
For the sake of model simplicity, the following assumptions have been made:
-
The body structure is rigid and symmetric.
-
The rotors are on the same height as the center of gravity and rotate around an axis that passes through the center of gravity.
-
The rotors are rigid.
-
Thrust and drag torque are proportional to the square of rotor’s speed.
-
The linear and angular velocity of the body are small.
-
The dynamics of the tilting motors are independent of the rotational speed of rotors.
-
The thrust and drag torque produced by one rotor is independent of the thrust and torque of the other rotors, that is the produced air flows do not interference.
While most of these assumptions will cause little or no deviation of the flight characteristics of the real world system from the derived system model, the last assumption which ignores rotor interference is likely to have a significant impact. However in our experience and flight tests we have found that with a well tuned controller this influence can be treated as an unmodeled disturbance.
Iii-C Rigid Body Model
For the modeling of the body dynamics, the Newton-Euler formalism was used. The general form of this formalism is the following:
(1) |
with
being the 3-dimensional identity matrix and
the moment of inertia of the system.Iii-D Motor Dynamics
The motor dynamics of the DC motors of the rotors are modeled as a first order system.
(2) |
with being the desired angular velocity and is the motor’s time constant. Similarly, the closed loop tilting velocity dynamics are modeled as first order system with time constant . Moreover, the tilting velocity is saturated to model the maximum possible tilting velocity as follows
(3) |
where is the maximum possible tilting velocity.
Iii-E Aerodynamics
The aerodynamics modeling transfers the actual angular velocities and tilting angles into the forces and moments acting on the center of gravity of the body. Given the stated assumptions of low body velocities, we can neglect the aerodynamic drag of the main body and assume that the thrust and reaction torque are proportional to the square of the rotational velocity of the rotors. The force and torque produced by one rotor is given by:
(4) | ||||
(5) |
with being the lift force coefficient and the drag torque coefficient. These forces and moments are produced in the z-direction of the coordinate frames of the rotor. The forces have a negative sign, since the z-axis is pointing downwards.
The forces and moments are then rotated into the body frame.
(6) | ||||
(7) |
with
(8) | ||||
(9) |
where is the rotation matrix of the i-th rotor frame to the body frame and is the distance from the center of gravity to the i-th rotor. The relation between the forces, moments, tilting angles and angular velocities can then be described by the following equation.
(10) |
where (see Equation (11)), and with representing cosine and representing sine.
(11) |
will henceforth be referred to as the allocation matrix. For a conventional quad- or hexacopter this allocation matrix is static. However, for this project it is a function of the tilting angles , which is an advantage, since the total force vector can be directed in any orientation through the selection of appropriate tilting angles. In addition to this, the matrix is of size , as opposed to the size utilized by a conventional hexacopter. This means the system can produce a desired force in all three axes, instead of just the z-direction. Since the matrix has full rank in most configurations (it’s singular in some special cases such as when all ’s are zero and other more complex cases), all forces and moments can be produced independently, meaning that translation and rotation of the platform can be controlled independently.
Iv Control
Iv-a Control structure
In this section, we present a baseline controller for the Voliro platform. Given the omni-directional nature of the platform, it is possible to decouple the position and attitude dynamics as the actuation forces and torques are independent. Therefore, we consider two separate controllers for position and attitude reference tracking. A cascade control structure is employed to control the attitude as shown in Figure 7.

Desired forces and torques are achieved by changing the angular velocity and the orientation of each propeller. Therefore, the control allocation problem becomes challenging, as for the 6 dof output, there are control inputs. We introduce the position and attitude controllers, followed by a novel solution to this control allocation problem.
Iv-B Position control
The position control is based on a PID controller with a feed forward terms that generates a desired force vector in the vehicle body frame . The position error is defined as the difference between desired and estimated position . The position control law is given by:
(12) |
where is the rotation matrix between the body frame and inertial frame, , are the proportional, derivative and integral gains respectively, is the vehicle mass and is the gravity vector.
Iv-C Attitude control
The attitude controller consists of two cascade controllers, an outer loop for the attitude control that generated desired body rates and a rate controller that generates desired moments. The attitude controller is based on quaternion error which is given by:
(13) |
The desired body rate is generated from the vector part of the quaternion error as follows:
(14) |
where is a tuning parameter. Note that the sign of the real part of the quaternion error is used to avoid the unwinding phenomena.
The desired moments are computed as follows:
(15) |
where is the rate controller gain, is the estimated angular velocity, is the center of mass offset, and is the vehicle’s inertia matrix.
Iv-D Control allocation
The control allocation problem deals with finding rotors speed and rotor angular positions to satisfy equation (10). Solving this equation is challenging for two reasons. The first reason is that any solution is not unique due of the over-actuated nature of the platform. The second reason is that the rotors angular positions appear in a non-linear fashion in the allocation matrix (11). One approach to solve this problem would be to perform a nonlinear least square optimization. However, the computation time required and available computation resources on-board the platform inhibit such a solution. Another approach is to use a nonlinear model predictive attitude controller [17] that generates near optimal rotors speed and tilting angles commands. This approach is appealing as it can easily account for tilting angles dynamics, but could be computationally expensive. Note that this allocation needs to be solved at high rate to allow the system to perform in an agile manner.
Here we propose an approach to transform the nonlinear allocation problem into a linear problem through variable transformation. We show that this solution also satisfies the constraint of positive rotors speed. To this end, we decompose the force generated by each rotor as shown in equation (4) along the vertical axis and the lateral axis of the rotor. We define vertical and lateral forces of the rotor as follows
(16) | ||||
(17) |
We also define the vector of dimension of all vertical and lateral forces as follows
(18) |
By rearranging equation (10) we obtain
(19) |
where is a static allocation matrix of dimensions that doesn’t depend on the rotors orientation . At this point, we can easily invert equation (19) to calculate from a desired wrench . We use the Moore-Penrose pseudo inverse of to calculate as follows
(20) |
Since the system is under-determined, the Moore-Penrose pseudo-inverse is the minimum norm solution of Equation (19). It is straight forward to show that the norm of is proportional to the sum of the fourth power of rotor speeds as shown below.
(21) |
This minimization leads to more consistent and equally distributed angular velocities as well as a reduction of power consumption, which all are desirable.
Now, obtaining the actual rotor speed and rotor orientation for each rotor is straight forward and can be done by solving the system of equations in (16). We have
(22) | ||||
(23) |
This approach means that the calculation of motor speeds and tilting angles can be done by the simple multiplication of a matrix by a vector. This allows it to be calculated at a rate of several hundred Hz on the small micro-controller found in the Pixhawk. It has to be noticed however, that allocating the actuator commands by using the pseudo-inverse may result in inadmissible rotor speeds that are higher than physically possible. This may occur even if the desired forces and moments lie in the set of attainable forces and moments. One approach to overcome this is the exploitation of the null space of the pseudo-inverse. The exploration of this remains for further analysis.
There is one major disadvantage of this allocation method, namely that the tilting angles and the angular velocities are nonlinearly coupled. Therefore, it is difficult to constrain them separately. This means, that this allocation doesn’t account for the slower dynamics of the tilting angles. An example of a situation in which this becomes a critical issue is hovering at a roll angle of . In this configuration one of the three rotor axes is completely vertical. Therefore, the two thrust motors on this axis can only produce a force in horizontal direction. Hence, they are not used for counteracting gravity, but for disturbance rejection and horizontal position stabilization. These two motors are required to constantly rotate back and forth at a high rate to provide the desired counteracting moments and forces. The dynamics of the tilting motors are, however, much slower than that of the thrust motors and as a result can not keep up with the desired allocation commands. This leads to forces and moments being produced in directions that have not been commanded. To overcome this, the allocation was modified to exclude these two motors in this particular configuration. In this configuration, the system flies with the four remaining ones, which still allow it to control all six DoF. This is further explained in [18].
V Evaluation
V-a Simulation

The controller was tested in simulation. This simulation uses Gazebo[19] as a physics environment and to model the tilting motors. To simulate the modeled sensors and the thrust motors the RotorS plugin[20] is used. The sensor data was sent via the MAVLink protocol111pixhawk.org/dev/mavlink to the software in the loop (SITL) version of the PX4 software. The model of the system was then loaded into this environment. It can be seen in Figure 8. Similar to the actual system, the commands are sent via ROS to the controller.
V-B Experimental Results
In this section, the experimental results are presented. The position and orientation of the vehicle are determined with an external motion capture system, which is sent to the flight controller at and fused with the onboard IMU. To showcase the vehicle’s capabilities, two different maneuvers are demonstrated. Both maneuver are unfeasible to perform for a standard multicopter. Moreover, we show experimental results where the Voliro platform is able to interact and move along a wall.
V-B1 Free Flight Experiments
![]() |
![]() |
![]() |
![]() |
![]() |
![]() |
![]() |
![]() |
The first experiments show the rotation of the vehicle around the body’s y-axis from its initial horizontal orientation to upside down and back. During this maneuver the other desired rotations and positions are set to zero. The results of this experiment are shown in Figure 10. This maneuver is conducted in a slow manner to display the vehicle’s capability to stabilize in all the rotations around the y-axis.

The second experiments displays a horizontal translation in x- and y-direction. The desired rotation around the x-axis is set constant to while the other rotations are set to zero. The results are shown in Figure 11.

V-B2 Wall Interaction Experiments
To enable physical interaction with the wall, a three spheres module that can roll passively is mounted on the Voliro platform as shown in Figure 12. The module is passively compliant to improve interaction stability and to reduce oscillation during contact. The phases to achieve physical interaction with the wall can be summarized as follows:
-
Transition from horizontal flight to vertical flight, which is achieved at pitch , as shown in Figure 12(a).
-
Approach the wall while maintaining a pitch angle of until a contact is established with the compliant three spheres module. This phase is shown in Figure 12(b).
-
Driving on the wall is achieved by generating force vector using a simple proportional controller. Tracking a circle on the wall is shown in Figure 12(c).
More details about wall interaction control and experiments are available here [21].

![]() |
![]() |
![]() |
The experiments demonstrate the vehicle’s omni-directionality. It is able to obtain all orientations along one rotation axis and to perform translations at an inclined orientation. However, the controller is not able to counteract all of the system’s translational and rotational dynamics, such that the position and the orientation are still slightly coupled. This can be partially explained by the slower dynamics of the tiling motors when compared to the thrust motors. The experiments showed that the roll and pitch angles are better tracked than the position. This is because the rotation dynamics is controlled mainly by changing the rotational speed of the rotors and utilizes their fast dynamics.
Deviations in position and in yaw are generally corrected by the tilting of the rotors and are more sensitive to their slow dynamics.
While flying at a pitch angle , the allocation demands for inadmissible rotor speeds, leading to two thrust motors becoming saturated. This is further discussed in section IV-D. Nevertheless, the system is still able to track the desired position and orientation.
Vi Discussion and Conclusion
This work has presented the Voliro platform, a hexacopter with tiltable rotors. We demonstrated how this basic idea can be used to achieve omnidirectional maneuverability while avoiding wasting energy on generation of counteracting forces which is an issue that inhibits the use of fixed orientation rotors in omni-directional designs. We presented the mechanical design of the platform and a compact tiltable rotor. We also presented a control scheme with an innovative control allocation technique. The main advantage of the allocation technique presented in this work is the simplicity and the limited computation effort required to computed tilting angles and rotor speed. However, problems caused by slow rotor tilting dynamics remain an open issue. In various experiments, we demonstrated a transition from horizontal to upside flight and physical interaction with a wall. While the increased maneuverability gives rise to a broader scope of applications, some of them may require a powering tether in order to overcome the limitations imposed by battery life. In conclusion, tiltable rotor multirotor showed great capabilities and can push the boundaries of what is currently achievable by standard fixed orientation multirotors.
Acknowledgment
The authors would like to acknowledge Philipp Andermatt, Cliff Li. Alexis Müller, Kamil Ritz, and Kevin Schneider who were part of the Voliro focus project team and contributed in numerous ways to the development and deployment of the Voliro prototypes.
References
- [1] A. Bircher, M. Kamel, K. Alexis, H. Oleynikova, and R. Siegwart, “Receding horizon path planning for 3d exploration and surface inspection,” Autonomous Robots, pp. 1–16, 2016.
- [2] A. Gawel, M. Kamel, T. Novkovic, J. Widauer, D. Schindler, B. P. von Altishofen, R. Siegwart, and J. Nieto, “Aerial picking and delivery of magnetic objects with mavs,” in 2017 IEEE International Conference on Robotics and Automation (ICRA), May 2017, pp. 5746–5752.
- [3] K. Steich, M. Kamel, P. Beardsleys, M. K. Obrist, R. Siegwart, and T. Lachat, “Tree cavity inspection using aerial robots,” in 2016 IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS), October 2016.
- [4] A. Girard, A. Howell, and J. Hedrick, “Border patrol and surveillance missions using multiple unmanned air vehicles,” in Decision and Control, 2004. CDC. 43rd IEEE Conference on, 2004.
- [5] A. Bircher, M. Kamel, K. Alexis, M. Burri, P. Oettershagen, S. Omari, T. Mantel, and R. Siegwart, “Three-dimensional coverage path planning via viewpoint resampling and tour optimization for aerial robots,” Autonomous Robots, vol. 40, no. 6, pp. 1059–1078, 2016.
- [6] T. Nägeli, L. Meier, A. Domahidi, J. Alonso-Mora, and O. Hilliges, “Real-time planning for automated multi-view drone cinematography,” ACM Transactions on Graphics (TOG), vol. 36, no. 4, p. 132, 2017.
- [7] S. Verling, B. Weibel, M. Boosfeld, K. Alexis, M. Burri, and R. Siegwart, “Full Attitude Control of a VTOL tailsitter UAV,” in International Conference on Robotics and Automation (ICRA), 2016.
- [8] L. Furieri, T. Stastny, L. Marconi, R. Siegwart, and I. Gilitschenski, “Gone with the Wind: Nonlinear Guidance for Small Fixed-Wing Aircraft in Arbitrarily Strong Windfields,” in Proceedings of the American Control Conference (ACC), 2017.
- [9] D. Brescianini and R. D’Andrea, “Design, Modeling and Control of an Omni-Directional Aerial Vehicle,” in International Conference on Robotics and Automation (ICRA), 2016.
- [10] M. Ryll, H. H. Bulthoff, and P. R. Giordano, “Modeling and Control of a Quadrotor UAV with Tilting Propellers,” in International Conference on Robotics and Automation (ICRA), 2012.
- [11] M. Ryll, H. H. Bülthoff, and P. R. Giordano, “First flight tests for a quadrotor uav with tilting propellers,” in Robotics and Automation (ICRA), 2013 IEEE International Conference on. IEEE, 2013, pp. 295–302.
- [12] M. Ryll, D. Bicego, and A. Franchi, “Modeling and control of FAST-Hex: A fully-actuated by synchronized-tilting hexarotor,” in International Conference on Intelligent Robots and Systems (IROS), 2016.
- [13] M. Ryll, G. Muscio, F. Pierri, E. Cataldi, G. Antonelli, F. Caccavale, and A. Franchi, “6D physical interaction with a fully actuated aerial robot,” in International Conference on Robotics and Automation (ICRA), 2017.
- [14] A. Oosedo, S. Abiko, S. Narasaki, A. Kuno, A. Konno, and M. Uchiyama, “Flight Control Systems of a Quad Tilt Rotor Unmanned Aerial Vehicle for a Large Attitude Change,” in International Conference on Robotics and Automation (ICRA), 2015.
- [15] E. Kaufman, K. Caldwell, D. Lee, and T. Lee, “Design and Development of a Free-Floating Hexrotor UAV for 6-DOF Maneuvers,” in Aerospace Conference, 2014.
- [16] L. Meier, D. Honegger, and M. Pollefeys, “PX4: A node-based multithreaded open source robotics framework for deeply embedded platforms,” in Robotics and Automation (ICRA), 2015 IEEE International Conference on, may 2015.
- [17] M. Kamel, K. Alexis, M. Achtelik, and R. Siegwart, “Fast nonlinear model predictive control for multicopter attitude tracking on so (3),” in Control Applications (CCA), 2015 IEEE Conference on. IEEE, 2015, pp. 1160–1166.
- [18] O. Elkhatib, “Control allocation of a tilting rotor hexacopter,” Bachelor thesis, Swiss Federal Institute of Technology, ETH Zurich, 2017.
- [19] N. Koenig and A. Howard, “Design and use paradigms for gazebo, an open-source multi-robot simulator,” in 2004 IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS) (IEEE Cat. No.04CH37566), vol. 3, Sept 2004, pp. 2149–2154 vol.3.
- [20] F. Furrer, M. Burri, M. Achtelik, and R. Siegwart, Robot Operating System (ROS): The Complete Reference (Volume 1). Cham: Springer International Publishing, 2016, ch. RotorS—A Modular Gazebo MAV Simulator Framework, pp. 595–625.
- [21] P. Wulkop, “Development of a controller enabling a tilting rotor hexacopter to move omnidirectionally on a wall,” Bachelor thesis, Swiss Federal Institute of Technology, ETH Zurich, 2017.