![]() |
WarpTwin
Documentation for WarpTwin models and classes.
|
/******************************************************************************
* Copyright (c) ATTX INC 2025. All Rights Reserved.
*
* This software and associated documentation (the "Software") are the
* proprietary and confidential information of ATTX, INC. The Software is
* furnished under a license agreement between ATTX and the user organization
* and may be used or copied only in accordance with the terms of the agreement.
* Refer to 'license/attx_license.adoc' for standard license terms.
*
* EXPORT CONTROL NOTICE: THIS SOFTWARE MAY INCLUDE CONTENT CONTROLLED UNDER THE
* INTERNATIONAL TRAFFIC IN ARMS REGULATIONS (ITAR) OR THE EXPORT ADMINISTRATION
* REGULATIONS (EAR99). No part of the Software may be used, reproduced, or
* transmitted in any form or by any means, for any purpose, without the express
* written permission of ATTX, INC.
******************************************************************************/
/*
Magnetometer model header file
Author: James Tabony
*/
/*
Metadata for MS GUI:
imdata = {"displayname" : "Magnetometer",
"exclude" : False,
"category" : "Sensors"
}
aliases = {"bias_initial" : "Bias",
"min_mag_field_strength" : "Minimum Mag. Strength",
"max_mag_field_strength" : "Maximum Mag. Strength",
"mount_frame" : "Spacecraft Body",
"mount_position__mf" : "EXCLUDE",
"mount_alignment_mf" : "EXCLUDE",
"resolution" : "EXCLUDE",
"rate_hz" : "Rate Hz",
"seed_value" : "EXCLUDE",
"mag_field_model_frame" : "Mag. Field Model Frame",
"latency" : "EXCLUDE",
"gaussian_noise" : "Noise",
"walking_bias_std" : "EXCLUDE",
"scale_factor_std" : "EXCLUDE",
"truth_mag_field__model" : "Truth Mag. Field",
"meas_mag_field__mag" : "Meas. Mag. Field",
"truth_mag_field__mag" : "EXCLUDE",
"is_valid" : "Meas. Validity Flag",
"operational_power_draw" : "Operational Power Draw",
"mass" : "Mass",
"current_power_draw" : "Current Power Draw",
}
*/
#ifndef MODELS_SENSORS_MAGNETOMETER_H
#define MODELS_SENSORS_MAGNETOMETER_H
#include "simulation/Model.h"
#include "frames/Frame.h"
#include "models/support/MarkovUncertaintyModel.h"
#include "monitors/RateMonitor.h"
#include "utils/LatencyUtil.hpp"
namespace warptwin {
/**
* @brief Configurable magnetometer model which takes input from simplified or high fidelity magnetic field models
*
* This model simulates a simple magnetometer with bias and noise. This model requires use of
* an external magnetic field model (e.g. simple dipole model, IGRF, WMM). The magnetometer
* model requires an input to the frame of the magnetic field model output.
*
* HOW DOES THIS MODEL HANDLE NOISE:
* The typical 3-axis magnetometer has uncorrelated noise in each of the three
* measurement axes. The additive noise in the magnetometer can be modeled as
* Gaussian white noise with a standard deviation that is dependent on measurement
* rate, temperature, and oversampling ratio.
*
* The typical magnetometer also has some bias even after factory calibration. This
* bias is not completely stable so the bias random walk does need to be modeled for
* the majority of missions with a duration. The bias random walk standard deviation
* is constant as a function of time, however it is usually not constant as a function
* of temperature. Most accelerometer data sheets will have temperature effects on the
* bias stability.
*
* The majority of magnetometers exhibit some amount of multiplicative noise that is
* very temperature and age dependent. This is due to the Micro-Electrical-Mechanical
* systems that are in the sensor being expanded and decompressed with temperature
* effects. Additionally, the internal polynomial function that is used to convert the
* measured voltage to a magnetic field measurement through an ADC is subject to manufacturing
* tolerances. The percent error standard deviation should be very small, around 0.1%-0.5%
*
* Typically the noise profile (additive, multiplicative, and biasing) are all dependent
* on temperature. Because of this, the model has the values as inputs. The user has the
* choice to repeatedly input new noise characteristics based on an external model, or input
* them once and it be held constant.
*
* Author: James Tabony <james.tabony@attx.tech>
*/
/// @brief Sensor output struct for latency model, its members are the same as the model outputs. Its default constructor populates members with defualt output values
struct _magnetometer_output_struct {
CartesianVector3 meas_mag_field__mag;
bool is_valid;
// Default constuctor (should populate with model defualt outputs)
_magnetometer_output_struct()
: meas_mag_field__mag(CartesianVector3({0.0, 0.0, 0.0})),
is_valid(false) {}
// Custom constructor
_magnetometer_output_struct(CartesianVector3 meas_mag_field__mag, bool is_valid)
: meas_mag_field__mag(meas_mag_field__mag),
is_valid(is_valid) {}
};
MODEL(Magnetometer)
public:
// Model params
// NAME TYPE DEFAULT VALUE
START_PARAMS
/** The initial bias in magnetometer measurement output described as a three-element vector in meters/second^2.
* Default is no bias. Must be set before model startup. */
SIGNAL(bias_initial, CartesianVector3, CartesianVector3({0.0, 0.0, 0.0}))
/** The minimum magnetic field strength that the sensor can record in each axis. Default is -800 µT assuming input
* unit is in nanoTesla. (same unit as input) */
SIGNAL(min_mag_field_strength, double, -800000.0)
/** The maximum magnetic field strength that the sensor can record in each axis. Default is 800 µT assuming input
* unit is in nanoTesla. (same unit as input) */
SIGNAL(max_mag_field_strength, double, 800000.0)
/** The vehicle frame relative to which the sensor is mounted and aligned. This is most
* typically the body frame of a spacecraft or other vehicle. mount_position__mf and mount_alignment_mf
* are described relative to this frame. */
SIGNAL(mount_frame, Frame*, nullptr)
/** The position of the sensor in the mount frame, represented in the default simulation
* unit (meters by default. pretty much always meters) */
SIGNAL(mount_position__mf, CartesianVector3, CartesianVector3({0.0, 0.0, 0.0}))
/** The alignment of the magnetometer relative to the mount frame. Rotation from sensor frame to mount frame */
SIGNAL(mount_alignment_mf, clockwerk::Quaternion, clockwerk::Quaternion({1.0, 0.0, 0.0, 0.0}))
/** The measurement resolution. The output value will be some multiple of this value. If the
* value is left at zero, an infinite resolution will be assumed, i.e. no data loss/quantization.
* From a data sheet, this value can be computed as (measurement range) / 2^(bits per measurement) . (same unit as input) */
SIGNAL(resolution, double, 0.0)
/** The rate at which the sensor generates an output, in hertz. This value must be some
* positive (non-zero) integer. (Hz) */
SIGNAL(rate_hz, int, 0)
/** Value to seed the internal RNG for this model. */
SIGNAL(seed_value, int, 0)
/** External magnetic field model output frame, see inputs for further explanation. */
SIGNAL(mag_field_model_frame, Frame*, nullptr)
/** Latency of the magnetometer, millisecond value for the amount of delay in sim time for
* the correct values to be reflected in the outputs. Must be set before executive startup.
* Defaults to no delay. (milliseconds) */
SIGNAL(latency, int, 0)
/** Power draw of the magnetometer. This value may or may not be the peak power draw provided by most
* data sheets. This value is the expected power draw of a sensor when operational. (Watts) */
SIGNAL(operational_power_draw, double, 0.0)
/** Mass of the magnetometer. (kg) */
SIGNAL(mass, double, 0.0)
END_PARAMS
// Model inputs
// NAME TYPE DEFAULT VALUE
START_INPUTS
/** The one-sigma Gaussian noise in magnetometer measurement output described as a three-element vector
* in same unit as input. Default is no noise. */
SIGNAL(gaussian_noise, CartesianVector3, CartesianVector3({0.0, 0.0, 0.0}))
/** The one-sigma Gaussian noise in the magnetometer bias drift described as a three-element vector
* in (input unit)/sqrt(second) e.g. nT/sqrt(sec). Default is no walking-bias drift. */
SIGNAL(walking_bias_std, CartesianVector3, CartesianVector3({0.0, 0.0, 0.0}))
/** The one-sigma scale percent increase/decrease of the measurement. Default is no scaling. */
SIGNAL(scale_factor_std, CartesianVector3, CartesianVector3({0.0, 0.0, 0.0}))
/** The local magnetic field of the sensor gathered from an external
* magnetic field model (e.g. dipole, IGRF, WMM), expressed in the
* model output frame. (input unit) */
SIGNAL(truth_mag_field__model, CartesianVector3, CartesianVector3({0.0, 0.0, 0.0}))
END_INPUTS
// Model outputs
// NAME TYPE DEFAULT VALUE
START_OUTPUTS
/** Output time tied to measurements. Output time is exactly the navigation time
* (see SimTimeManager for configuration), without latency (instantaneous) but
* but with a rate that mirrors output rate */
SIGNAL(output_time, clockwerk::Time, clockwerk::Time(0, 0))
/** The measured output magnetic field produced by the magnetometer describing the
* local magnetic vector of the sensor frame expressed in sensor frame coordinates
* with appropriate bias, noise, latency, and rate limiting. (Same unit as input) */
SIGNAL(meas_mag_field__mag, CartesianVector3, CartesianVector3({0.0, 0.0, 0.0}))
/** The "perfect" output magnetic field produced by the magnetometer describing the
* local magnetic field of the sensor frame expressed in sensor frame coordinates
* without bias and noise. This is an informational parameter.
* This value is not effected by latency. (Same unit as input) */
SIGNAL(truth_mag_field__mag, CartesianVector3, CartesianVector3({0.0, 0.0, 0.0}))
/** Boolean value to notify if the output measurement is valid (i.e. boolean for
* blackout-zones). True = not in blackout-zone, False = in blackout-zone. */
SIGNAL(is_valid, bool, false)
/** Power draw of the sensor. This value is populated when the model is active, and zero
* when the model is deactivated. Allows the user to create duty cycles and power budgets. (Watts) */
SIGNAL(current_power_draw, double, 0.0)
END_OUTPUTS
/// @brief Accessor for the sensor's frame
clockwerk::DataIO<Frame*> sensor_frame = clockwerk::DataIO<Frame*>(this, "sensor_frame", &_sensor_frame);
/// @brief Accessor for the internal bias and noise model
/// @return Pointer to the bias noise model
warptwin::MarkovUncertaintyModel* biasNoiseModel() {return &_sensor_noise_model;}
/// @brief Accessor for the internal rate monitor model
/// @return Pointer to the rate monitor model
warptwin::RateMonitor* rateMonitor() {return &_rate_monitor;}
int16 activate() override;
int16 deactivate() override;
protected:
int16 start() override;
int16 execute() override;
/// @brief Function to configure sensor -- runs in all constructors
void _configureInternal();
/// @brief The sensor frame in which all measurements will be taken
Frame _sensor_frame;
/// @brief The bias and noise model for sensor output.
MarkovUncertaintyModel _sensor_noise_model;
/// @brief Rate monitor to control the rate at which the sensor runs
RateMonitor _rate_monitor;
/// @brief Temporary variable to hold the bias vector at last function call
CartesianVector3 _previous_bias;
/// @brief Temporary variable to hold the truth magnetic field vector in the sensor frame
CartesianVector3 _truth_mag_field__mag;
/// @brief Temporary variable to hold the perturbed acceleration with and without gravity
CartesianVector3 _perturbed_mag;
/// @brief Temporary variable for checking if sensor is in deadzone. Each element of vector corresponds to an axis
std::array<bool, 3> _in_deadzone;
/// @brief Internal latency model, templated to the sensor output struct
LatencyUtil<_magnetometer_output_struct> _latency_model;
/// @brief Temporary variable for the latest recorded output added to latency model and dummy output for stepping though latency
_magnetometer_output_struct _last_output, _latency_return;
};
}
#endif