Skip to content
vdm_c

vdm_c

Project ID: 3187

The first real-time VDM-based navigation prototype

VDMc

The VDM method is based on an aerodynamic model of the aircraft obtained by fluid mechanics methods. This model is then used as the process of an extended Kalman filter for the navigation, while the IMU and GNSS data are both treated as updates. The methodology to obtain this vehicle dynamic model is detailed in @vdm. The architecture of the extended Kalman filter is inspired from @scorpion. However, the different state blocks must be more tightly coupled, since they are not completely independent. Although the program is meant to be platform-independent, it still needs some work to implement additional platforms automatically. The current platforms are a custom-made fixed-wing UAV called TOPOplane2, and a delta-wing called ConcordeS1 (in a temporary new branch ConcodeS1). This WiKi focuses on the TOPOplane2 platform.

topoplane

Where to start?

  • Below is an introduction to the general software architecture and repository layout.
  • Installation instructions are available here.
  • The core of the software is the timer algorithm, which is described here.
  • The autogeneration of the source files from a platform's model using Mathematica is described here
  • The complete list of wiki pages is visible on the right or here

Software architecture

There are two concurrent main loops in VDMc:

  • The main thread receives data from ROS and queues it in circular buffers. It only runs the ROS callbacks through ros::spin().
  • The EKFThread creates an EKF object, runs the Kalman filter algorithm and outputs the navigation solution through the configured channels.

The EKF class implements the extended Kalman filter. This class maintains the filter state and covariance, and implements the propagation and update algorithms. It also defines the process() function to run the backpropagation algorithm.

The platform_TP2 class defines everything that is platform-specific. Most notably, it defines the states, the VDM model and the associated process noise. The states are divided in blocks of related states, and it is possible to decide at run-time whether each block is estimated or assumed constant. For the TOPOplane2 platform, there are currently 9 blocks for a total of 68 states, which are specified below

Block name # of states Description
Xn 13 Navigation states (pose, velocity and angular rates)
Xp 21 VDM parameters (aerodynamic coefficients)
Xa 4 Actuator states (propeller speed and control surface positions)
Xa_d 12 Actuator dynamic coefficients (deprecated)
Xw 3 Wind velocity
Xe 6 IMU biases
XL_IMU 3 IMU lever-arm (deprecated)
XB_IMU 3 IMU bore-sight (deprecated)
XL_GPS 3 GNSS antenna lever-arm (deprecated)

The FilterTimer class is an abstract class representing an event affecting the EKF at regular intervals (although this interval might be infinite to provide one-shot actions). Examples of implementations include sensor updates, input from the control commands, initialization (if it depends on external data), and output of the estimated states to various channels. More information is available here.

The MeasProcessor class is an abstract class representing a sensor. It contains a model of the h function linking the observed quantities to the states, as well as the derivative of this function and the noise model of the sensor. There are three implementations of this class for different sensors: measprocessorGNSSpos, measprocessorGNSSvel and measprocessorIMU. More details can be found here.

The different <data_type>Receiver classes are used to connect to ROS, receive data and add it to the appropriate buffer. The ROS callbacks run in the main thread, so every shared memory access from within the callbacks must be protected. The CircularBuffer class is safe to use without additional thread synchronization if one thread appends data to it and another one removes data at the beginning.

Structure of the repository

The VDMc repository is hosted on EPFL's gitlab. It has the following structure:

  • src/ The C++ source files (*.cpp)
  • include/ The C++ header files (*.h)
  • config/ Example configuration folder (*.ini)
  • test/ Everything related to unit tests. Including the CMakeLists.txt used to compile the tests.
  • doxygen/html/ Doxygen output generated in August 2021
  • doc/ Draw.io flowchart of the backpropagation algorithm
  • functionGenerator/ The automatized linearization and .cpp source files generation of platform's models
  • results/ Contains the script compare.py used to parse the program output
  • CMakeLists.txt The main build script, used to compile VDMc with CMake
  • package.xml Definition of the ROS package of VDMc

Flight examples

To test the software, two recorded flight data for the TOPOPlane2 and the ConcodeS1 platforms are available here with explanations.

License

As this software is based on the following patent, the code can not be distributed in the current form openly without a license.

A temporary solution is proposed, for those who would like tp have the source code: an academic/non-commercial license must be obtained from the EPFL Technology Transfer Office without a cost upon a request through the following contact: info.tto@epfl.ch using "[EPFL invention # 6.1501] [US 62/173,443 ]" in the email's subject. Upon reception of a signed license, the code would be distributed by contacting the main contributors of the code at: gabriel.laupre@epfl.ch, aman.sharma@epfl.ch, and simon@gilgien.net, or directly to the Technology Transfer Office to guarantee anonymity.