API Documentation
Loading...
Searching...
No Matches
OrientationSensor.h
Go to the documentation of this file.
1/*--------------------------------------------------------------------------------------------
2Copyright (c) 2019, NDEVR LLC
3tyler.parke@ndevr.org
4 __ __ ____ _____ __ __ _______
5 | \ | | | __ \ | ___|\ \ / / | __ \
6 | \ | | | | \ \ | |___ \ \ / / | |__) |
7 | . \| | | |__/ / | |___ \ V / | _ /
8 | |\ |_|_____/__|_____|___\_/____| | \ \
9 |__| \__________________________________| \__\
10
11Subject to the terms of the Enterprise+ Agreement, NDEVR hereby grants
12Licensee a limited, non-exclusive, non-transferable, royalty-free license
13(without the right to sublicense) to use the API solely for the purpose of
14Licensee's internal development efforts to develop applications for which
15the API was provided.
16
17The above copyright notice and this permission notice shall be included in all
18copies or substantial portions of the Software.
19
20THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED,
21INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR
22PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE
23FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR
24OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER
25DEALINGS IN THE SOFTWARE.
26
27Library: Hardware
28File: OrientationSensor
29Included in API: True
30Author(s): Tyler Parke
31 *-----------------------------------------------------------------------------------------**/
32#pragma once
33#include <NDEVR/Device.h>
34#include <NDEVR/Matrix.h>
35#include <QObject>
36namespace NDEVR
37{
50
51 /**--------------------------------------------------------------------------------------------------
52 Enum: MagnetometerState
53
54 \brief Used by OrientationSensor to display the current state of any available magnetometer
55 \ingroup Hardware Magnetometer
56 *-----------------------------------------------------------------------------------------------**/
75 class StationModel;
76 class Calibration;
77 class IMUCalibrator;
78 class DesignObjectLookup;
79 class MagneticCalibrationData;
80
81 /**--------------------------------------------------------------------------------------------------
82 Class: OrientationSensor
83
84 \brief Used to report the orientation of a Hardware object within 3D space
85 \ingroup Hardware Magnetometer Orientation Gyro Accelerometer
86 *-----------------------------------------------------------------------------------------------**/
88 {
89 Q_OBJECT
90 public:
91 OrientationSensor(const Model& model, ProgressInfo* log, QObject* parent = nullptr);
92 [[nodiscard]] virtual Time getGyroCalibrationTime() const;
93 [[nodiscard]] virtual MagnetometerState magnetometerState() const { return m_magnetometer_state; };
94 [[nodiscard]] virtual GyroState gyroState() const;
95 [[nodiscard]] virtual Matrix<fltp08> lastOrientation() const;
96 [[nodiscard]] static Matrix<fltp08, 3, 3> calculateDeviation(TimeSpan time, const Vector<4, fltp08>& start, const Vector<4, fltp08>& end);
97 [[nodiscard]] static Angle<fltp08> calculateNorthFacing(const Matrix<fltp08, 3, 3>& offset_mat);
98 [[nodiscard]] static Matrix<fltp08, 3, 3> offsetCalibration(TimeSpan time_since_calibration, const Matrix<fltp08, 3, 3>& current_orientation, const Matrix<fltp08, 3, 3>& dev_matrix);
99 [[nodiscard]] virtual bool usingAccelerometer() const { return m_using_accelerometer; }
100 [[nodiscard]] virtual bool usingCompass() const { return m_using_compass; }
101 [[nodiscard]] virtual bool usingGyro() const { return m_using_gyro; }
102 [[nodiscard]] virtual bool isGyroUpdating() const { return m_is_gyro_updating; }
103 [[nodiscard]] virtual bool hasLockedYaw() const;
104 [[nodiscard]] virtual bool hasLockedRoll() const;
105 [[nodiscard]] const Vector<3, Angle<fltp08>>& driftRate() const { return m_angle_drift_rate; }
106 [[nodiscard]] Vector<3, Angle<fltp08>> driftValue() const;
107 [[nodiscard]] Vector<3, Angle<fltp08>> userSpecifiedOffsets() const { return m_user_specified_offsets; };
108 [[nodiscard]] Vector<3, Angle<fltp08>> deviceOffsets() const { return m_device_specified_offsets; };
109 [[nodiscard]] virtual bool isLocked() const { return m_is_locked; }
110 [[nodiscard]] virtual TranslatedString calibrationMessage() const;
112 void setUserSpecifiedOffsets(const Vector<3, Angle<fltp08>>& user_specified_offsets) { m_user_specified_offsets = user_specified_offsets; }
113 void setDeviceOffsets(Vector<3, Angle<fltp08>> device_offsets) { m_device_specified_offsets = device_offsets; }
114 virtual bool requestAccelerationBiasLimit(fltp04 bias_limit) { UNUSED(bias_limit); return false; }
115 virtual bool requestUsingAccelerometer(bool using_accelerometer);
116 virtual Ray<3, fltp08> calibratedMagnetometerVector() const { return m_calibrated_magnetomer_vector; };
117 virtual Ray<3, fltp08> rawMagnetometerVector() const { return m_raw_magnetometer_vector; };
118 virtual Angle<fltp08> compassAngle() const { return Constant<Angle<fltp08>>::Invalid; };
119 virtual bool requestUsingCompass(bool using_compass);
120 virtual bool requestUsingGyro(bool using_gyro, bool reset_state);
121 virtual bool requestGyroCalibration() { return false; }
122 virtual void lockRoll(bool lock_roll, Angle<fltp08> roll = Constant<Angle<fltp08>>::Invalid, Angle<fltp08> yaw = Constant<Angle<fltp08>>::Invalid);
123 virtual void lockYaw(bool lock_yaw, Angle<fltp08> lock_heading = Constant<Angle<fltp08>>::Invalid);
124 virtual bool supportsFixed() const { return true; }
125 virtual bool supportsModes() const { return false; }
126 virtual bool supportsRodded() const { return true; }
127 virtual void setDriftRate(const Vector<3, Angle<fltp08>>& drift_rate);
128 virtual void setCalibrator(IMUCalibrator* imu_calibrator);
129#if NDEVR_CALIBRATION
130 virtual Calibration createCalibrationObject(DesignObjectLookup* lookup);
131#endif
133 virtual bool requestMagnetometerCalibration(bool) { return false; }
134 virtual bool requestApplyMagnetometerCalibration() { return false; }
135 virtual bool needsMagnetometerCalibration() const { return false; }
136 virtual bool hasCalibratedDrift() const { return m_has_calibrated_drift; }
139 void setFromGravityAcceleration(const Vector<3, fltp08>& acceleration_vector);
140 virtual void setFromQuaternion(const Vector<4, fltp08>& quaternion);
142 void createCalibrationOffset(const Matrix<fltp08>& map_from, const Matrix<fltp08>& map_to);
143 void setFromAngles(const Vector<3, Angle<fltp08>>& angles);
145 virtual void clearCurrentDrift();
146 IMUCalibrator* calibrator() const { return m_imu_calibrator; }
147 [[nodiscard]] virtual Ray<3, fltp08> referenceDirection() const { return Ray<3, fltp08>(1.0, 0.0, 0.0); }
148 [[nodiscard]] virtual UUID calibrationID() const { return m_calibration_id; };
149 protected:
150 [[nodiscard]] virtual Vector<3, Angle<fltp08>> lastOrientationAngle() const;
151 signals:
156 protected:
157 Ray<3, fltp08> m_calibrated_magnetomer_vector = Constant<Ray<3, fltp08>>::Invalid;
158 Ray<3, fltp08> m_raw_magnetometer_vector = Constant<Ray<3, fltp08>>::Invalid;
165 Time m_calibration_time;//The time when the current calibration was created
170 IMUCalibrator* m_imu_calibrator = nullptr;
175 bool m_using_gyro = false;
176 bool m_using_compass = false;
177 bool m_using_accelerometer = false;
178 bool m_is_gyro_updating = false;
179 bool m_is_locked = false;
180 bool m_has_calibrated_drift = false;
181 bool m_gyro_calibration_requested = false;
182 };
183}
#define UNUSED(expr)
Definition BaseValues.hpp:406
#define HARDWARE_API
Definition DLLInfo.h:74
The primary angle storage class for this API. Stores an angle in an optimized format.
Definition StringStream.h:408
A core class where all Design Objects including models, materials, and geometries are stored.
Definition DesignObjectLookup.h:65
Definition Device.h:48
Definition IMUCalibrator.h:27
Stores magnetic calibration data as a Model including the transformation and calibration points.
Definition MagneticCalibration.h:16
Definition Matrix.hpp:176
A core class that represents a node on model heirarchy. This node may contain a Geometry or.
Definition Model.h:58
Used to report the orientation of a Hardware object within 3D space.
Definition OrientationSensor.h:88
static Matrix< fltp08, 3, 3 > offsetCalibration(TimeSpan time_since_calibration, const Matrix< fltp08, 3, 3 > &current_orientation, const Matrix< fltp08, 3, 3 > &dev_matrix)
static Angle< fltp08 > calculateNorthFacing(const Matrix< fltp08, 3, 3 > &offset_mat)
virtual Ray< 3, fltp08 > referenceDirection() const
Definition OrientationSensor.h:147
virtual Vector< 3, Angle< fltp08 > > lastOrientationAngle() const
virtual bool hasCalibratedDrift() const
Definition OrientationSensor.h:136
fltp04 m_calibration_percent
Definition OrientationSensor.h:166
Vector< 3, Angle< fltp08 > > m_angle_drift_rate
Definition OrientationSensor.h:163
virtual bool supportsRodded() const
Definition OrientationSensor.h:126
virtual GyroState gyroState() const
virtual bool usingGyro() const
Definition OrientationSensor.h:101
virtual void lockRoll(bool lock_roll, Angle< fltp08 > roll=Constant< Angle< fltp08 > >::Invalid, Angle< fltp08 > yaw=Constant< Angle< fltp08 > >::Invalid)
virtual Matrix< fltp08 > lastOrientation() const
Vector< 3, Angle< fltp08 > > quaternionToAngle(const Vector< 4, fltp08 > &quaternion) const
GyroState m_gyro_state
Definition OrientationSensor.h:172
virtual bool requestUsingCompass(bool using_compass)
virtual Ray< 3, fltp08 > calibratedMagnetometerVector() const
Definition OrientationSensor.h:116
const Vector< 3, Angle< fltp08 > > & driftRate() const
Definition OrientationSensor.h:105
virtual bool requestGyroCalibration()
Definition OrientationSensor.h:121
virtual bool hasLockedYaw() const
Angle< fltp08 > m_yaw_lock
Definition OrientationSensor.h:168
MagnetometerState m_magnetometer_state
Definition OrientationSensor.h:173
AccelerometerState m_acceleromter_state
Definition OrientationSensor.h:174
Time m_calibration_time
Definition OrientationSensor.h:165
Vector< 3, Angle< fltp08 > > driftValue() const
Angle< fltp08 > m_roll_lock_reference_yaw
Definition OrientationSensor.h:169
virtual bool supportsModes() const
Definition OrientationSensor.h:125
Vector< 3, Angle< fltp08 > > m_user_specified_offsets
Definition OrientationSensor.h:161
Vector< 3, Angle< fltp08 > > userSpecifiedOffsets() const
Definition OrientationSensor.h:107
virtual bool isLocked() const
Definition OrientationSensor.h:109
virtual MagneticCalibrationData * magnetometerCalibrationObject()
Definition OrientationSensor.h:132
virtual bool hasLockedRoll() const
void setDeviceOffsets(Vector< 3, Angle< fltp08 > > device_offsets)
Definition OrientationSensor.h:113
IMUCalibrator * calibrator() const
Definition OrientationSensor.h:146
virtual Ray< 3, fltp08 > rawMagnetometerVector() const
Definition OrientationSensor.h:117
virtual bool needsMagnetometerCalibration() const
Definition OrientationSensor.h:135
void magnetometerCalibrationUpdatedSignal()
virtual void setDriftRate(const Vector< 3, Angle< fltp08 > > &drift_rate)
virtual bool usingAccelerometer() const
Definition OrientationSensor.h:99
virtual void clearCurrentDrift()
void setFromAngles(const Vector< 3, Angle< fltp08 > > &angles)
virtual void setCalibrator(IMUCalibrator *imu_calibrator)
virtual bool requestUsingGyro(bool using_gyro, bool reset_state)
fltp04 calibrationPercent() const
void setFromGravityAcceleration(const Vector< 3, fltp08 > &acceleration_vector)
void deploymentModeOptionsUpdatedSignal()
virtual void setFromQuaternion(const Vector< 4, fltp08 > &quaternion)
virtual Angle< fltp08 > compassAngle() const
Definition OrientationSensor.h:118
virtual UUID calibrationID() const
Definition OrientationSensor.h:148
virtual bool requestMagnetometerCalibration(bool)
Definition OrientationSensor.h:133
Vector< 3, Angle< fltp08 > > m_tilt_angle
Definition OrientationSensor.h:159
Matrix< fltp08 > m_calibration_offset
Definition OrientationSensor.h:162
Angle< fltp08 > m_roll_lock
Definition OrientationSensor.h:167
virtual TranslatedString calibrationMessage() const
void setUserSpecifiedOffsets(const Vector< 3, Angle< fltp08 > > &user_specified_offsets)
Definition OrientationSensor.h:112
virtual MagnetometerState magnetometerState() const
Definition OrientationSensor.h:93
OrientationSensor(const Model &model, ProgressInfo *log, QObject *parent=nullptr)
virtual bool isGyroUpdating() const
Definition OrientationSensor.h:102
void setCalibrationOffset(const Matrix< fltp08 > &offset)
Vector< 3, Angle< fltp08 > > gravityAccelerationToAngle(const Vector< 3, fltp08 > &acceleration_vector)
virtual bool requestUsingAccelerometer(bool using_accelerometer)
UUID m_calibration_id
Definition OrientationSensor.h:171
virtual Time getGyroCalibrationTime() const
virtual bool requestAccelerationBiasLimit(fltp04 bias_limit)
Definition OrientationSensor.h:114
Time m_angle_drift_start_time
Definition OrientationSensor.h:164
virtual void lockYaw(bool lock_yaw, Angle< fltp08 > lock_heading=Constant< Angle< fltp08 > >::Invalid)
Vector< 3, Angle< fltp08 > > m_device_specified_offsets
Definition OrientationSensor.h:160
static Matrix< fltp08, 3, 3 > calculateDeviation(TimeSpan time, const Vector< 4, fltp08 > &start, const Vector< 4, fltp08 > &end)
virtual bool requestApplyMagnetometerCalibration()
Definition OrientationSensor.h:134
virtual bool usingCompass() const
Definition OrientationSensor.h:100
void createCalibrationOffset(const Matrix< fltp08 > &map_from, const Matrix< fltp08 > &map_to)
virtual bool supportsFixed() const
Definition OrientationSensor.h:124
Vector< 3, Angle< fltp08 > > deviceOffsets() const
Definition OrientationSensor.h:108
A light-weight base class for Log that allows processes to update, without the need for.
Definition ProgressInfo.hpp:48
Definition Vertex.hpp:317
Represents a timestamp with utilities for manipulation and conversion.
Definition Time.h:54
Stores a time span, or difference between two times, with an optional start time.
Definition TimeSpan.h:46
Any text displayed to the user should be defined as a TranslatedString which allows the.
Definition TranslatedString.h:13
A universally unique identifier (UUID) is a 128-bit number used to identify information in computer s...
Definition UUID.h:62
A fixed-size array with better performance compared to dynamic containers.
Definition Vector.hpp:60
Definition ACIColor.h:37
float fltp04
Defines an alias representing a 4 byte floating-point number.
Definition BaseValues.hpp:125
AccelerometerState
Definition OrientationSensor.h:65
@ e_no_accelerometer
Definition OrientationSensor.h:66
@ e_accelerometer_invalid
Definition OrientationSensor.h:68
@ e_accelerometer_valid
Definition OrientationSensor.h:67
SensorQuality
Definition OrientationSensor.h:71
@ e_valid_quality
Definition OrientationSensor.h:72
@ e_invalid_quality
Definition OrientationSensor.h:73
GyroState
Definition OrientationSensor.h:39
@ e_gyro_invalid
Definition OrientationSensor.h:41
@ e_stabalizing_temp
Definition OrientationSensor.h:45
@ e_validating_drift
Definition OrientationSensor.h:47
@ e_initializing
Definition OrientationSensor.h:43
@ e_calculating_drift
Definition OrientationSensor.h:46
@ e_no_gyro
Definition OrientationSensor.h:40
@ e_needs_reset
Definition OrientationSensor.h:48
@ e_disabled
Definition OrientationSensor.h:44
@ e_gyro_valid
Definition OrientationSensor.h:42
MagnetometerState
Used by OrientationSensor to display the current state of any available magnetometer.
Definition OrientationSensor.h:58
@ e_no_compass
Definition OrientationSensor.h:59
@ e_compass_valid
Definition OrientationSensor.h:60
@ e_calculating_bias
Definition OrientationSensor.h:62
@ e_compass_invalid
Definition OrientationSensor.h:61
Defines for a given type (such as sint04, fltp08, UUID, etc) a maximum, minimum, and reserved.
Definition BaseValues.hpp:230