Assemble, Launch, Explore, and Develop Mini Drones Using an All-Inclusive Kit

By Stephen Evanczuk

Contributed By DigiKey's North American Editors

Four rotor drones, or quadcopters, continue to serve increasingly important roles in a wide variety of applications, but their design remains a complex endeavor that combines knowledge of mechanical, electronic, and software subsystems. Although designers are well capable of learning what’s required, a drone development kit can offer a head start, bringing together all the elements required to gain experience with drone flight theory and practice.

This article describes an STMicroelectronics development kit that offers developers a mini quadcopter drone that is simple to assemble, yet fully demonstrates the complex flight control systems behind any multirotor aerial vehicle.

Quadcopter dynamics

In their most popular form, quadcopters provide a particularly stable platform for a wide range of applications such as aerial photography, field inspection, surveillance, and more. Unlike fixed-wing aircraft or even helicopters with their variable-pitch rotors, fixed-pitch multirotor drones are relatively simple in design and easy to construct thanks to the wide availability of small efficient DC motors.

The mechanical simplicity and aerodynamic stability of these drones arise from the coordinated use of their rotors to control maneuvers, rather than the use of flight surfaces in aircraft or a combination of main rotor and tail assembly in helicopters.

In a quadcopter, the pair of motors located across the diagonal of the airframe spin in the same direction as each other but in the opposite direction of the other two motors. If all four motors spin at the same speed, the drone can ascend, descend, or hover. If a diagonal pair spins faster than the other pair, the drone will yaw, rotating about its center of gravity while remaining on the same horizontal plane (Figure 1, left).

Figure 1: Drones maneuver by using different combinations of rotor speed such as speeding up both motors in a diagonal pair (M2, M4) in a yaw maneuver (left) or speeding up one diagonal motor (M2) while slowing its diagonal counterpart (M4) to complete a more complex pitch-roll maneuver (right). (Image source: STMicroelectronics)

If the speed of the forward (or aft) rotors is changed, the drone will pitch up or down like a fixed-wing aircraft ascending or descending in flight. A similar adjustment of the port or starboard pair will cause the drone to roll, rotating about its centerline. Drones can easily achieve more complex flight attitudes (combinations of pitch, yaw, and roll) by adjusting the relative speeds of a diagonal pair of motors or of a single motor (Figure 1, right).

The drone’s flight control system is responsible for modifying the speed of the appropriate rotors to achieve the desired flight attitude needed to complete the desired maneuver.

In practice, the control system needs to constantly adjust rotor speed not just in performing a turn, for example, but even during level flight to correct for perturbing force such as wind, thermals, or turbulence. Even for a mini drone operating indoors, a flight control system needs the ability to measure the difference between the drone’s actual attitude and the desired attitude.

For an engineer, the problem of correcting rotor speeds according to some error signal is a familiar control loop feedback problem solved with a proportional-integral-derivative (PID) controller. The only remaining conceptual challenge is finding a method to measure the drone’s attitude, but that problem is readily solved using high precision smart sensors to feed Euler angle calculations.

Euler angles represent the XYZ plane orientation of an object relative to some xyz plane of reference, where the two planes intersect along a line N (Figure 2). The Euler angles are then defined as:

  • α, the angle between the x axis and N
  • ß, the angle between the z and Z axes
  • γ, the angle between N and the X axis

Figure 2: Euler angles (α, ß, γ) describe the relative orientation of a rotated frame (XYZ) with respect to a fixed reference frame (xyz) that intersect in line N. (Image source: Wikimedia Commons CC BY 3.0)

For a flight control system, the object plane and reference plane correspond directly with the current orientation (XYZ) of the drone and its desired attitude (xyz). In turn, the Euler angles indicate the axial rotations required to bring the drone into the desired attitude. Although mechanical gyroscopes have for years provided the raw data used to determine current orientation, the availability of high precision microelectromechanical system (MEMS) accelerometers and gyroscopes have enabled application of this method even in lightweight mini drones.

Today, drones of all shapes and sizes rely on a sensor-based attitude and heading reference system (AHRS) that feeds position information into Euler angle calculations. In turn, the Euler angles are used to create the error signal for a PID controller that manages motor speeds to achieve the desired flight maneuver. The challenge lies in implementing this approach with software on a mobile platform capable of completing the calculations and motor corrections with the necessary speed and precision.

The STMicroelectronics STEVAL-DRONE01 mini drone kit and associated software provide a working example of this approach and serves as a foundation for exploring the details of drone flight control systems.

Flight-ready mini drone kit

The STEVAL-DRONE01 kit packages all the components required to build a small quadcopter. Along with a plastic airframe, the kit includes four 8.5 x 20 millimeter (mm), 3.7 volt, 8520 coreless DC motors each capable of about 35 grams of thrust with the included 65 mm propellers. The motors and propellers are provided in two pairs configured for clockwise and counterclockwise rotation. When fully assembled with the 3.7 volt lithium-ion polymer (LiPo) battery, the drone’s gross weight, or all-up weight (AUW), is less than 70 grams, providing the approximate 2:1 thrust-to-weight ratio preferred for drone operations.

Aside from its mechanical components, however, the kit’s centerpiece is the STMicroelectronics STEVAL-FCU001V1 flight controller unit (FCU) board and associated software package, which together provide the flight control system capabilities mentioned earlier. The FCU board is a sophisticated, power efficient, multi-sensor system with Bluetooth low energy (BLE) connectivity (Figure 3).

Figure 3: The STMicroelectronics STEVAL-FCU001V1 flight controller unit is a complete battery-powered multi-sensor system with BLE connectivity and DC motor drive capability. (Image source: STMicroelectronics)

Built around the 32-bit Arm® Cortex®-M4-based STMicroelectronics STM32F401 microcontroller, the board includes three different MEMS sensors for measuring different characteristics related to drone positioning and navigation, including:

  • The STMicroelectronics LSM6DSL iNEMO inertial measurement unit (IMU) integrates an accelerometer and gyroscope needed for AHRS functionality
  • The STMicroelectronics LIS2MDL magnetometer provides data for implementing direction-detection features
  • The STMicroelectronics LPS22HD pressure sensor provides data for determining vertical positioning with an 8 centimeter (cm) resolution

On the sensor input side, the FCU’s STM32F401 microcontroller connects with each sensor across a shared SPI bus. On the motor output side, the microcontroller’s TIM4 general purpose timer provides the pulse-width modulated (PWM) signal used to control the gates of the STMicroelectronics STL6N3LLH6 MOSFET power transistors that drive the drone’s DC motors.

For receiving user control commands, the FCU provides two options: users can control the drone from a smartphone with a Bluetooth connection using the on-board STMicroelectronics SPBTLE-RF module, which includes the company’s BlueNRG-MS transceiver with a complete power optimized Bluetooth stack. Alternatively, users can employ a standard radio control (RC) PWM-based remote control (remocon) console. Finally, for battery and power management, the board includes an STMicroelectronics STC4054 Lithium-ion battery charger IC and LD39015 low dropout (LDO) regulator.

As indicated in Figure 3, the FCU also supports connection to an external electronic speed controller (ESC) such as the STMicroelectronics STEVAL-ESC001V1. An ESC allows a system to drive more robust three-phase motors, allowing use of the FCU in more powerful quadcopter designs.

To simplify flight preparation and control, the kit comes preconfigured to use the Bluetooth connection option with the STMicroelectronics STDrone Android mobile app. Designed as a virtual remocon console, the app provides users with a simple flight control interface with control icons and two virtual joysticks (Figure 4).

Figure 4: The STMicroelectronics STDrone Android mobile app provides users with a virtual remote control console for operating a mini drone built with the company’s STEVAL-DRONE01 development kit. (Image source: STMicroelectronics)

After assembly, the drone operator can use the STDrone app to launch and control the drone with their mobile device. Before takeoff, the operator needs to place the drone on a flat surface and touch the app’s calibration icon until it turns green, meaning calibration has completed. For safety, the drone motors are initially disabled through software, requiring the user to “arm” the drone by tapping on another app icon. At this point, the app user interfaces functions like a remocon console, allowing the user to move the virtual joysticks to adjust drone rotor speed and flight attitude.

Although the ultralight STMicroelectronics lacks the mass and power needed for extensive outdoor use, drone operators who might operate the mini drone outdoors need to be aware of drone flight restrictions in their intended area of operation. Mini drone operators might not be required to become licensed operators or register very small drones of this class. Nevertheless, they do need to comply with requirements.

These flight requirements include maintaining line of sight, observing 400 ft. maximum altitude, and avoiding no-fly zones such as within 5 miles of an airport in the US, or 1 km in the UK, avoiding operation near sporting events or emergency operations, and others. Drone operators can use mobile apps such as the Federal Aviation Administration’s B4UFLY app in the US or the National Air Traffic Agency (NATS) Drone Assist app in the UK, each of which provide information on local airspace restrictions based on the user’s GPS location.

Flight control software

For engineers, a compelling feature of the STMicroelectronics drone kit’s FCU is its associated software package, which STMicroelectronics maintains in an open-source github repository. Built on the STMicroelectronics STM32Cube framework, the application is layered upon Bluetooth stack middleware and an underlying driver layer. The driver layer handles the details of hardware interaction using the STM32Cube hardware abstraction layer (HAL) and STEVAL-FCU001V1 board support package (BSP), which includes drivers for the FCU board devices described earlier.

The software architecture for the application is built around three separate modules, one each for remote control, position determination, and PID control (Figure 5):

  • The remote control module handles input from the STDrone mobile app or from an RC remocon console, collecting data values from the app or converting remocon PWM data, before translating those values to Euler angles for the desired flight attitude.
  • The position determination module collects accelerometer and gyroscope data from the LSM6DSL IMU for use in the AHRS position estimation needed to calculate the Euler angles for the drone’s current flight attitude. Data from the LIS2MDL magnetometer and LPS22HD pressure sensor are collected but not used for drone flight control calculations in the software version available as of this writing.
  • The PID control module completes the position error calculation using the difference between Euler angles for desired versus current attitude. Using conventional PID control methods, this module uses that error signal to adjust the speed of each motor to bring the drone to the desired attitude.

Figure 5: The STMicroelectronics mini drone flight control software builds its functionality around separate modules for handling remote control input (blue boxes, labelled (1)), position determination (red boxes, (2)), and PID control (dark blue box, (3)). The PID control then drives the quadcopter’s four motors. (Image source: STMicroelectronics)

Using this functional architecture, the drone application combines these modules in the workflow needed to translate user commands for maneuvers into the motor speed adjustments required to perform those maneuvers (Figure 6). Although complex in overall functionality, the main loop for updating flight control parameters is relatively straightforward.

Figure 6: The STMicroelectronics mini drone flight control software implements a work flow that continuously reads sensor data to update the drone’s current flight attitude and adjust the speed of the drone’s four motors to achieve the desired flight combination of thrust, pitch, roll, and yaw. (Image source: STMicroelectronics)

After a series of calls to initialize the hardware and software systems, the main application routine, main.c, enters an infinite loop (Listing 1). Within this main loop, the update process uses a series of calls to perform the core flight control algorithms described previously.

Copywhile (1)
  {
  . . .
        
    if (tim9_event_flag == 1)
    {     // Timer9 event: frequency 800Hz
      tim9_event_flag = 0;
  . . .
           


      // AHRS update, quaternion & true gyro data are stored in ahrs
      ahrs_fusion_ag(&acc_ahrs, &gyro_ahrs, &ahrs);

      // Calculate euler angle drone
      QuaternionToEuler(&ahrs.q, &euler_ahrs);

      
      #ifdef REMOCON_BLE
      
          gRUD = (joydata[2]-128)*(-13);
          gTHR = joydata[3]*13;
          gAIL = (joydata[4]-128)*(-13);
          gELE = (joydata[5]-128)*13;
          
          /* joydata[6]: seek bar data*/
          /* joydata[7]: additional button data
                        first bit: Takeoff (0 = Land,  1 = Takeoff)
                        second bit: Calibration When it changes status is active
                        third bit: Arming (0 = Disarmed,  1 = Armed) */
          gJoystick_status = joydata[7];
          if ((gJoystick_status&0x04)==0x04){
            rc_enable_motor = 1;
            fly_ready = 1;
            BSP_LED_On(LED2);
          }
          else {
            rc_enable_motor = 0;
            fly_ready = 0;
          }
          

          if (connected){
            rc_connection_flag = 1;         /* BLE Remocon connected flag for enabling motor output */
            SendMotionData();
            SendBattEnvData();
            SendArmingData();            
          }
          else{
            rc_connection_flag = 0;
            gTHR=0;
            rc_enable_motor = 0;
            fly_ready = 0;
            BSP_LED_Off(LED1);
            BSP_LED_Off(LED2);
          }
          
          if (joydata[7]&0x02){
            rc_cal_flag = 1;
            BSP_LED_On(LED1);
          }
          
          
      #endif
          
      #ifdef REMOCON_PWM
  . . .
      #endif
      
      
      // Get target euler angle from remote control
      GetTargetEulerAngle(&euler_rc, &euler_ahrs);

  . . .
      
      FlightControlPID_OuterLoop(&euler_rc_fil, &euler_ahrs, &ahrs, &pid);
      
  . . .

    }
  . . .
  }

Within this loop, the microcontroller’s general purpose TIM9 timer serves as an event flag to control update rate. When the update timer event occurs, the main loop calls the AHRS update routine, ahrs_fusion_ag(), which uses the latest data from the accelerometer (acc_ahrs) and gyroscope (gyro_ahrs) to perform the sensor fusion calculations involved in the update. The resulting data, which is in quaternion form, is then used by the QuaternionToEuler() routine to calculate the Euler angles for the drone’s current flight attitude.

At this point in the main loop, the application collects data on the desired flight attitude using Bluetooth data if Bluetooth is enabled (#ifdef REMOCON_BLE), or the external RC console if that is enabled. Here, the code updates four variables that mirror conventional RC console data: gRUD (rudder position, or yaw), gAIL (aileron position, or roll), gELE (elevator position, or pitch), and gTHR (throttle position). After collecting that data, the loop uses the routine GetTargetEulerAngle() to calculate the Euler angles of the desired flight attitude as commanded by the drone operator. Prior to that calculation, however, this section of the loop demonstrates a feature of critical importance to the drone operator. If the Bluetooth connection has failed for any reason, the code shuts down the motors, which of course means an instant uncontrolled descent for the drone itself. An obvious, but non-trivial software extension might use the LIS2MDL magnetometer and LPS22HD pressure sensor data to return the drone to its starting point and land it in a controlled descent before shutting down the motors.

The main loop finally concludes with a call to FlightControlPID_OuterLoop() which updates the target values for the PID controller. Separately, FlightControlPID_innerLoop() runs as part of a sequence of operations performed in a callback to the interrupt associated with the TIM9 timer event, which is programmed to run at 800 Hertz (Hz). At each interrupt, the callback routine reads the sensors, filters the raw data, and updates first-in first-out (FIFO) buffers associated with the variables acc_ahrs and gyro_ahrs mentioned earlier as part of the main loop. Using this updated data on the drone’s current flight attitude, the callback routine invokes FlightControlPID_innerLoop(), which calculates new PWM values for each motor. The callback completes the update process by calling set_motor_pwm(), which sets the microcontroller’s PWM outputs to the new values.

Developers can easily explore alternative flight control scenarios by modifying the open-source software package with a number of tool chains including IAR Embedded Workbench for ARM, KEIL RealView microcontroller development kit for the STM32, and STMicroelectronics’s own free Windows-based System Workbench for STM32 integrated development environment (IDE). After compiling the modified code, developers can load their firmware into the FCU using an STMicroelectronics ST-LINK/V2 in-circuit debugger and programmer or STMicroelectronics STM32 Nucleo development board connected to the JTAG Serial Wire Debug (SWD) adaptor board provided with the kit.

Conclusion

Thanks to their simple mechanical design, multirotor drones have emerged as a popular choice for aerial photography, field inspection, surveillance, and many other applications. Using control algorithms fed by smart sensors, these drones employ sophisticated flight control software able to support stable operations and respond rapidly to operator commands for drone maneuvers.

Although developers can find and assemble the required mechanical, electrical, and software components on their own, a comprehensive mini drone development kit from STMicroelectronics provides an easier introduction to mini drone design and operation. By exploring and even modifying the associated open-source flight control software, developers can quickly gain experience in multirotor drone flight dynamics and control algorithms.

DigiKey logo

Disclaimer: The opinions, beliefs, and viewpoints expressed by the various authors and/or forum participants on this website do not necessarily reflect the opinions, beliefs, and viewpoints of DigiKey or official policies of DigiKey.

About this author

Image of Stephen Evanczuk

Stephen Evanczuk

Stephen Evanczuk has more than 20 years of experience writing for and about the electronics industry on a wide range of topics including hardware, software, systems, and applications including the IoT. He received his Ph.D. in neuroscience on neuronal networks and worked in the aerospace industry on massively distributed secure systems and algorithm acceleration methods. Currently, when he's not writing articles on technology and engineering, he's working on applications of deep learning to recognition and recommendation systems.

About this publisher

DigiKey's North American Editors