Sensors

The AURORA sensors library is merely an extension of the zephyr sensor driver api with helper functions, different sampling methods and specific workflows.

IMU

Interface for the inertial measurement unit (e.g. LSM6DSO32). Provides orientation (pitch and roll) and acceleration data.

ZBUS_CHAN_DECLARE(imu_data_chan)

ZBUS channel for IMU data.

int imu_poll(const struct device *dev)

Poll the IMU for acceleration data and sends it over the z-bus.

Parameters:

dev – Pointer to the IMU device.

Return values:
  • 0 – on success.

  • -errno – Negative errno on failure.

int imu_set_sampling_freq(const struct device *dev, int sampling_rate_hz)

Set the IMU accelerometer and gyroscope sampling frequency.

Parameters:
  • dev – Pointer to the IMU device.

  • sampling_rate_hz – Desired sampling rate in Hertz.

Return values:
  • 0 – on success.

  • -errno – Negative errno on failure.

int imu_init(const struct device *dev)

Initialize the IMU device.

Checks device readiness and configures the sampling frequency.

Parameters:

dev – Pointer to the IMU device.

Return values:
  • 0 – on success.

  • -ENODEV – if the device is not ready.

int imu_sensor_value_to_acceleration(const struct imu_data *data, double *acc_out)

calculate the average acceleration from IMU sensor values in m/s^2.

Parameters:
  • data – Pointer to the IMU sensor data

  • acc_out – Output for average acceleration in m/s^2. Must be valid pointer to a double.

Return values:
  • 0 – on success.

  • -EINVAL – if data or acc_out is NULL

int imu_sensor_value_to_orientation(const struct imu_data *data, double *angle_out)

Calculate the elevation angle from horizontal using IMU sensor values.

Uses CONFIG_IMU_UP_AXIS_* to pick the body axis pointing toward the rocket’s nose, so the result is independent of IMU mounting orientation. Convention matches the flight state machine’s arming thresholds:

  • 0 degrees = long axis horizontal

  • +90 degrees = long axis pointing up (nose toward sky)

  • -90 degrees = long axis pointing down

Only meaningful while gravity dominates (stationary / quasi-static); during powered flight, derive orientation from the attitude tracker.

Parameters:
  • data – Pointer to the IMU sensor data.

  • angle_out – Output: elevation angle in degrees, [-90, 90]. Must be a valid pointer to a double.

Return values:
  • 0 – on success.

  • -EINVAL – if data or angle_out is NULL.

IMU_NUM_AXES

Number of axes for IMU measurements.

struct imu_data
#include <imu.h>

IMU measurement data structure.

carries the measurement data from the IMU, including accelerometer and gyroscope readings for the x, y, and z axes. This struct is used as a z-bus message payload for IMU data updates

Attitude

Gyro-integrated body-frame gravity tracker. Anchors the body-frame “up” direction from a stationary accelerometer calibration window (typically during SM_ARMED), then propagates the gravity vector through flight using gyro measurements to project body-frame acceleration onto the world vertical axis for the filter.

Mounting orientation is configured via the CONFIG_IMU_UP_AXIS_* choice; calibration window length via CONFIG_IMU_CALIBRATION_SAMPLES.

int attitude_init(struct attitude *att)

Initialize (or reset) the attitude tracker.

Clears calibration sums, biases, and sets the body-frame gravity vector to the axis selected via CONFIG_IMU_UP_AXIS_*, pointing opposite to “up” (i.e. in the direction gravity pulls the rocket).

Parameters:

att – Pointer to tracker state.

Return values:
  • 0 – on success.

  • -EINVAL – if att is NULL.

int attitude_calibrate_sample(struct attitude *att, const double accel[3], const double gyro[3])

Add one IMU sample to the calibration accumulator.

Must only be called while the rocket is stationary.

Parameters:
  • att – Pointer to tracker state.

  • accel – Body-frame accelerometer reading in m/s^2.

  • gyro – Body-frame gyroscope reading in rad/s.

Return values:
  • 0 – on success.

  • -EINVAL – if any pointer is NULL.

  • -EALREADY – if calibration has already been finalized.

int attitude_calibrate_finish(struct attitude *att)

Finalize calibration and seed the body-frame gravity vector.

Averages the accumulated samples to compute accelerometer bias, gyro bias, and gravity magnitude, then seeds g_b from the Kconfig mounting axis. After this call attitude_is_calibrated returns non-zero.

Parameters:

att – Pointer to tracker state.

Return values:
  • 0 – on success.

  • -EINVAL – if att is NULL.

  • -ENODATA – if no samples have been accumulated.

int attitude_update(struct attitude *att, const double accel[3], const double gyro[3], double dt_s, double *accel_vert_out)

Propagate the gravity vector with a new IMU sample and project accelerometer into world vertical.

Subtracts biases, rotates the body-frame gravity vector by the gyro-integrated body rotation (small-angle Rodrigues), renormalizes, and returns the gravity-removed world-frame vertical acceleration (positive = up).

Parameters:
  • att – Pointer to tracker state.

  • accel – Body-frame accelerometer reading in m/s^2.

  • gyro – Body-frame gyroscope reading in rad/s.

  • dt_s – Elapsed time in seconds since the previous update.

  • accel_vert_out – Output: world-frame vertical accel in m/s^2, gravity-removed (positive = up).

Return values:
  • 0 – on success.

  • -EINVAL – if any pointer is NULL or dt_s <= 0.

  • -ENODATA – if calibration has not been finalized.

int attitude_is_calibrated(const struct attitude *att)

Query whether calibration has been finalized.

Parameters:

att – Pointer to tracker state.

Return values:

1 – if calibrated, 0 if not, -EINVAL if att is NULL.

ATTITUDE_NUM_AXES

Number of axes handled by the attitude tracker.

struct attitude
#include <attitude.h>

Attitude tracker state.

Barometer

Interface for the barometric pressure sensor. Can compute altitude estimates from pressure readings.

ZBUS_CHAN_DECLARE(baro_data_chan)

ZBUS channel for baro data.

int baro_measure(const struct device *dev)

Measure temperature and pressure from the barometric sensor and publish the data to the z-bus.

Parameters:

dev – Pointer to the barometric sensor device.

Return values:
  • 0 – on success.

  • -EINVAL – if dev is NULL

  • -errno – Other negative errno on failure.

int baro_init(const struct device *dev)

Initialize the barometric pressure sensor.

Checks device readiness and configures the oversampling rate.

Parameters:

dev – Pointer to the barometric sensor device.

Return values:
  • 0 – on success.

  • -ETIMEDOUT – if the device is not ready.

  • -EIO – if oversampling configuration fails.

int baro_set_reference(double ref_kpa)

Set the ground-level reference pressure.

Must be called before baro_sensor_value_to_altitude to establish the zero-altitude baseline. Typically called once at startup with the first valid pressure reading.

Parameters:

ref_kpa – Ground-level pressure in kilopascals.

Return values:
  • 0 – on success.

  • -EINVAL – if ref_kpa is not positive.

int baro_sensor_value_to_altitude(const struct sensor_value *press, double *altitude_out)

Convert a pressure reading to altitude AGL.

Uses the hypsometric formula (ISA troposphere model) with the reference pressure set by baro_set_reference.

Parameters:
  • press – Barometric pressure as sensor_value.

  • altitude_out – Altitude in meters above the reference level.

Return values:
  • 0 – on success.

  • -EINVAL – if press or altitude_out is NULL.

struct baro_data
#include <baro.h>

baro measurement data structure.

carries the measurement data from the baro including temperature and pressure readings. This struct is used as a z-bus message payload for baro data updates