Home » Blog » What is going on behind the calibration procedure of QGroundControl?

What is going on behind the calibration procedure of QGroundControl?

— Last modified: xiaoke das.xiaoke@gmail.com 2015/11/13 07:24

Every time I used QGroundControl for a new PIXHAWK flight management unit (FMU), I had to do some tedious and mysterious calibrations as in Figure 1. I didn't have much idea on what was going on behind the calibration procedure and I couldn't find much useful information over the internet either, apart from tons of videos instructing users how to carry out the calibration. Every time I just hoped things would work out of the box, until one day I couldn't bear this and started to dig out what was happening behind this easy-to-use interface.

Figure 1. Sensors config panel in QGroundControl.

The following is what I've found. Hope it'll be useful both for me and others who come across this article.

The Sensors Config Panel of QGroundControl

First download the source file of QGroundControl from its GitHub repository by

git clone --recursive https://github.com/mavlink/qgroundcontrol.git

By opening this project with an integrated development environment (IDE) QCreator, things become much easier. The code which implements the vehicle setup/configuration panel are found in folder qgroundcontrol/src/AutoPilotPlugins/PX4. The files SensorsComponentController.h and SensorsComponentController.cc contain detailed code for the calibration.

The code is listed as follows.

void SensorsComponentController::calibrateGyro(void)
{
    _startLogCalibration();
    _uas->startCalibration(UASInterface::StartCalibrationGyro);
}
 
void SensorsComponentController::calibrateCompass(void)
{
    _startLogCalibration();
    _uas->startCalibration(UASInterface::StartCalibrationMag);
}
 
void SensorsComponentController::calibrateAccel(void)
{
    _startLogCalibration();
    _uas->startCalibration(UASInterface::StartCalibrationAccel);
}
 
void SensorsComponentController::calibrateLevel(void)
{
    _startLogCalibration();
    _uas->startCalibration(UASInterface::StartCalibrationLevel);
}
 
void SensorsComponentController::calibrateAirspeed(void)
{
    _startLogCalibration();
    _uas->startCalibration(UASInterface::StartCalibrationAirspeed);
}

Now a mysterious object _uas comes out, apparently it is the link between the calibration interface and its background code. In src/uas/UAS.h and src/uas/UAS.cc I found the declaration and implementation of class UAS, to which the _uas object instance belongs. As commented in the source file, this class defines an Unmanned Aerial Vehicle object and corresponds to the real vehicle.

The two functions startCalibration and stopCalibration in the above code are two member functions of this class, responsible for the calibration of the vehicle. Now let's have a look at the implementation of the calibration function.

void UAS::startCalibration(UASInterface::StartCalibrationType calType)
{
    if (!_vehicle) {
        return;
    }
 
    int gyroCal = 0;
    int magCal = 0;
    int airspeedCal = 0;
    int radioCal = 0;
    int accelCal = 0;
    int escCal = 0;
 
    switch (calType) {
        case StartCalibrationGyro:
            gyroCal = 1;
            break;
        case StartCalibrationMag:
            magCal = 1;
            break;
        case StartCalibrationAirspeed:
            airspeedCal = 1;
            break;
        case StartCalibrationRadio:
            radioCal = 1;
            break;
        case StartCalibrationCopyTrims:
            radioCal = 2;
            break;
        case StartCalibrationAccel:
            accelCal = 1;
            break;
        case StartCalibrationLevel:
            accelCal = 2;
            break;
        case StartCalibrationEsc:
            escCal = 1;
            break;
        case StartCalibrationUavcanEsc:
            escCal = 2;
            break;
    }
 
    mavlink_message_t msg;
    mavlink_msg_command_long_pack(mavlink->getSystemId(),
                                  mavlink->getComponentId(),
                                  &msg,
                                  uasId,
                                  0,                                // target component
                                  MAV_CMD_PREFLIGHT_CALIBRATION,    // command id
                                  0,                                // 0=first transmission of command
                                  gyroCal,                          // gyro cal
                                  magCal,                           // mag cal
                                  0,                                // ground pressure
                                  radioCal,                         // radio cal
                                  accelCal,                         // accel cal
                                  airspeedCal,                      // airspeed cal
                                  escCal);                          // esc cal
    _vehicle->sendMessage(msg);
}
void UAS::stopCalibration(void)
{
    if (!_vehicle) {
        return;
    }
 
    mavlink_message_t msg;
    mavlink_msg_command_long_pack(mavlink->getSystemId(),
                                  mavlink->getComponentId(),
                                  &msg,
                                  uasId,
                                  0,                                // target component
                                  MAV_CMD_PREFLIGHT_CALIBRATION,    // command id
                                  0,                                // 0=first transmission of command
                                  0,                                // gyro cal
                                  0,                                // mag cal
                                  0,                                // ground pressure
                                  0,                                // radio cal
                                  0,                                // accel cal
                                  0,                                // airspeed cal
                                  0);                               // unused
    _vehicle->sendMessage(msg);
}

It turns out these two calibration functions actually send out mavlink messages to the vehicle, asking it to do the calibration.

Note there is a _vehicle object here which sends the message. This object is an implementation of class Vehicle. The class Vehicle is defined in src/Vehicle/Vehicle.cc and src/Vehicle/Vehicle.h. Not quite sure about the differences between this object and the UAS.

OK. It seems that the core functionality of calibration is actually performed in the vehicle, not in QGroundControl as I guessed before. QGroundControl merely performs a display and message passing task. We'll have to turn to the code of the vehicle to find out more about the calibration procedure. But before that, we need to check the definition of the constant MAV_CMD_PREFLIGHT_CALIBRATION, which is in file qgroundcontrol/src/QmlControls/MavlinkQmlSingleton.h and listed as follows.

typedef enum {
        ...
        MAV_CMD_PREFLIGHT_CALIBRATION=241, /* Trigger calibration. This command will be only accepted if in pre-flight mode. |Gyro calibration: 0: no, 1: yes| Magnetometer calibration: 0: no, 1: yes| Ground pressure: 0: no, 1: yes| Radio calibration: 0: no, 1: yes| Accelerometer calibration: 0: no, 1: yes| Compass/Motor interference calibration: 0: no, 1: yes| Empty|  */
        ...
    } Qml_MAV_CMD;

The number 241 is the key, and we'll use it later.