APIs description

Doxygen complete API documentation

Doxygen documentation Link to doxygen API documentation

Available classes

ABSTRACT_SENSOR

class ABSTRACT_SENSOR

Subclassed by ABSTRACT_BARO, ABSTRACT_IMU, ABSTRACT_MAG, ABSTRACT_SENSOR_I2C, ABSTRACT_SENSOR_SPI

Public Functions

inline bool checkBeginState()

return true if the sensor has been started correctly, false otherwise

struct SENSOR_CORRECTIONS

Structure representing sensor corrections.

Public Members

std::array<float, 3> xyzBias = {{0.F, 0.F, 0.F}}

XYZ bias values.

std::array<float, 3> xyzGain = {{1.F, 1.F, 1.F}}

XYZ gain values.

std::array<float, 5> degTemperatureAxis{{0.F, 0.F, 0.F, 0.F, 0.F}}

Temperature axis in degrees.

std::array<float, 5> driftValue = {{0.F, 0.F, 0.F, 0.F, 0.F}}

Drift values.

std::array<float, 5> sTimeAxis = {{0.F, 0.F, 0.F, 0.F, 0.F}}

Time axis in seconds.

ABSTRACT_SENSOR_SPI

class ABSTRACT_SENSOR_SPI : public ABSTRACT_SENSOR
struct SPI_CONF

ABSTRACT_SENSOR_I2C

class ABSTRACT_SENSOR_I2C : public ABSTRACT_SENSOR

ABSTRACT_MAG

class ABSTRACT_MAG : public ABSTRACT_SENSOR

Public Functions

void setConfig(const SENSOR_CORRECTIONS &correction)

Sets the configuration for the sensor.

This method sets the corrections (offsets, gains…) for the magnetometer.

Note

This method has to be called to apply the corections factors obtained after magnetometer calibration.

Parameters:

correction – The SENSOR_CORRECTIONS object containing the desired configuration.

const SENSOR_CORRECTIONS &getConfig()

Returns the configuration (corrections) struct used by the sensor.

Returns:

const SENSOR_CORRECTIONS& The reference to the sensor configuration.

const MAG_OUTPUT &getOutput()

Returns the output of the magnetometer.

Returns:

const MAG_OUTPUT& The reference to the magnetometer output.

bool calibMag(uint32_t msDuration)

Peudo-calibrates the magnetometer and outputs the corrections results.

This method calibrates the magnetometer and stores the corrections in the mMagCorrection struct. It also print the correction in Serial monitor and log it to SD card.

Parameters:

msDuration – The duration of the calibration in milliseconds.

Returns:

bool True if the calibration was successful, false otherwise.

struct AXIS

Structure representing the axes of a magnetometer.

struct MAG_OUTPUT

Structure representing the output of the magnetometer.

This structure contains the magnetometer data, IMU temperature, and timestamps.

ABSTRACT_IMU

class ABSTRACT_IMU : public ABSTRACT_SENSOR

Public Functions

void setConfig(SENSOR_TYPE type, const SENSOR_CORRECTIONS &correction)

Sets the configuration for the IMU sensor.

This function allows you to set the configuration for the IMU sensor (accelerometer, gyroscope, and magnetometer).

Parameters:
  • type – The type of sensor (accelerometer, gyroscope, or magnetometer)

  • correction – The sensor corrections to be applied.

const SENSOR_CORRECTIONS &getConfig(SENSOR_TYPE type)

Retrieves the configuration for a specific sensor type.

Parameters:

type – The type of sensor (accelerometer, gyroscope, or magnetometer)

Returns:

The configuration for the specified sensor type.

const IMU_OUTPUT &getOutput()

Retrieves the output of the IMU sensor.

Returns:

The output of the IMU sensor.

void calibGyro(uint32_t averagingNumber)

Calibrates the gyroscope by performing averaging over a specified number of samples.

Warning

This method should be called before using the gyroscope, with keeping the IMU for some time without moving. The calibration will be interrupted if the IMU is moved. You can call checkImmobility before calling this method

Parameters:

averagingNumber – The number of samples to average over for gyroscope calibration.

struct ABSTRACT_IMU_CFG

Configuration structure for the IMU sensor until 9 axis (including magnetometer)

This structure holds the sensor corrections for the accelerometer, gyroscope, and magnetometer.

struct AXIS
struct IMU_OUTPUT

Structure representing the output data from the IMU sensor.

This structure contains the following data:

  • gAccelData: Acceleration data in units of g.

  • dpsGyroData: Gyroscope data in units of degrees per second.

  • utMagData: Magnetometer data in units of microtesla.

  • degImuTemperature: IMU temperature in degrees.

  • usMagTimestamp: Timestamp for magnetometer data.

  • usGyroTimestamp: Timestamp for gyroscope data.

  • usAccelTimestamp: Timestamp for acceleration data.

  • usTempTimestamp: Timestamp for IMU temperature data.

ABSTRACT_BARO

class ABSTRACT_BARO : public ABSTRACT_SENSOR

Public Functions

void setConfig(const ABSTRACT_BARO_CFG &correction)

Sets the configuration (corrections) for the abstract barometer sensor.

This function allows you to set the configuration for the abstract barometer sensor. The configuration is specified by the ABSTRACT_BARO_CFG structure.

Parameters:

correction – The configuration to be set.

const ABSTRACT_BARO_CFG &getConfig()

Get the configuration (corrections) of the abstract barometer.

Returns:

const ABSTRACT_BARO_CFG& The configuration of the abstract barometer.

const BARO_OUTPUT &getOutput()

Get the output of the barometric sensor.

Returns:

const BARO_OUTPUT& The output of the barometric sensor.

void configureReferenceParameters(float referenceGroundPressure = ABSTRACT_BARO_ENUM::BARO_VALUES::INVALID_PRESSURE, float referenceGroundTemperature = ABSTRACT_BARO_ENUM::BARO_VALUES::INVALID_TEMPERATURE, float referenceGroundAltitude = ABSTRACT_BARO_ENUM::BARO_VALUES::INVALID_ALTITUDE, uint16_t nbAveragingSamples = ABSTRACT_BARO_ENUM::BARO_VALUES::DEFAULT_NB_AVERAGING_VALUES)

Set the Reference Pressure and temperature for precise absolute measures.

The altitude will be calculated with this reference pressure and temperature. If some parameters are not set, default parameters will be used.

Parameters:
  • referenceGroundPressure – ground pressure at ground level

  • referenceGroundAltitude – altitude at ground level if available from external source (map, GPS…). Parameters (groundOffset, referencePressureAtSeaLevel) will be updated accordingly. Otherwise, if not specified, we will consider referenceSeaPressure as 1013.25 and groundPressure will be converted to altitude with this value, which will give a groundOffset.

struct ABSTRACT_BARO_CFG

Configuration settings for the abstract barometer sensor.

Correction values for BARO + reference pressure and temperature for altitude computation

struct BARO_OUTPUT

Structure representing the output of the barometric sensor.

This structure contains the following information:

  • hPaPressure: The pressure in hPa.

  • degTemperature: The temperature in degrees Celsius.

  • mAbsoluteAltitude: The altitude in meters compared to sea level.

  • mRelativeAltitude: The altitude in meters compared to ground level (assuming ground pressure reference has been set).

  • usPressureTimestamp: The timestamp of the pressure measurement in microseconds.

  • usTemperatureTimestamp: The timestamp of the temperature measurement in microseconds.

namespace ABSTRACT_BARO_ENUM
struct BARO_VALUES
#include <libDM_abstract_baro.hpp>

This file contains basic definitions and methods specific to barometric sensors.

The BARO_VALUES struct provides constants and utility functions for working with barometric sensor data. It defines default values, invalid thresholds, and validation functions for pressure, temperature, and altitude.

Public Static Functions

static inline bool isPressureValid(float pressure)

Check if the pressure value is valid.

Parameters:

pressure – The pressure value to check.

Returns:

true if the pressure is valid, false otherwise.

static inline bool isTemperatureValid(float temperature)

Check if the temperature value is valid.

Parameters:

temperature – The temperature value to check.

Returns:

true if the temperature is valid, false otherwise.

static inline bool isAltitudeValid(float altitude)

Check if the altitude value is valid.

Parameters:

altitude – The altitude value to check.

Returns:

true if the altitude is valid, false otherwise.