11#include "sygah-endpoints.hpp"
12#include "sygah-mimu.hpp"
13#include "sygsp-mimu_units.hpp"
15namespace sygaldry {
namespace sygsp {
31 slider<
"proportional feedback"
32 ,
"proportional feedback gain coefficient"
33 , float, 0.0f, 10.0f, 3.0f
37 ,
"integral feedback gain coefficient"
38 , float, 0.0f, 10.0f, 0.0f
41 slider<
"accelerometer influence"
42 ,
"accelerometer gain coefficient; reflects confidence in the accelerometer data"
43 , float, 0.0f, 1.0f, 0.25f
46 slider<
"magnetometer influence"
47 ,
"magnetometer gain coefficient; reflects confidence in the magnetometer data"
48 , float, 0.0f, 1.0f, 1.0f
51 slider<
"movement threshold"
52 ,
"threshold of jerk magnitude below which the device is considered as stationary"
53 , float, 0.0f, 32.0f, 0.0001f
56 slider<
"gyroscope bias smoothing"
57 ,
"IIR filter coefficient for gyro bias smoothing filter; higher value results in more smoothing/lower cutoff"
58 , float, 0.0f, 1.0f, 0.99f
61 bng<
"initialize",
"trigger sensor re-initialization"> initialize;
62 toggle<
"calibrate magnetometer"
63 ,
"enable tracking magnetometer data to estimate and remove sensor bias; "
64 "the previous bias estimate is reset when compensation is enabled"
65 > calibrate_magnetometer;
75 ,
"quaternion representation of the orientation of the sensor in the global frame"
79 ,
"quaternion representation of the orientation of the global bases in the sensor frame"
83 ,
"special orthogonal matrix of the sensor basis vectors expressed in the global frame"
87 ,
"special orthogonal matrix of the global basis vectors expressed in the sensor frame"
90 slider<
"norm of gravity",
"estimated strength of gravity relative to one standard gravity (9.80665 m/s/s)"
91 , float, 0.995f, 1.002f
93 slider<
"gravity measurements",
"count of gravity measurements"
94 ,
unsigned int, 0, 1<<16
98 ,
"m/s/s",
"estimated acceleration due to motion expressed in the sensor frame of reference"
102 ,
"m/s/s",
"estimated acceleration due to motion expressed in the performance frame of reference"
105 , float, -16.0f, 16.0f
106 ,
"g",
"previous measurement of acceleration; used in the estimation of jerk"
109 , float, -32.0f, 32.0f
110 ,
"g/s",
"approximate signal analogous to the derivative of acceleration in the sensor frame"
114 ,
"rad/s",
"estimated gyroscope sensor bias"
117 , float, -4900.0f, 4900.0f
118 ,
"uT",
"component-wise maximum of magnetometer values measured while calibrating bias compensation"
121 , float, -4900.0f, 4900.0f
122 ,
"uT",
"component-wise minimum of magnetometer values measured while calibrating bias compensation"
125 , float, -4900.0f, 4900.0f
126 ,
"uT",
"estimated magnetometer sensor bias"
130 ,
"rad/s",
"estimated angular rate based on fused sensor measurements"
133 , float, -20.0f, 20.0f
134 ,
"integral feedback through the complementary filter"
137 ,
"boolean indication of whether the sensor is stationary (1) or movement is detected (0)"
static constexpr float rad_per_deg
Definition sygsp-mimu_units.hpp:40
static constexpr float mss_per_g
Definition sygsp-mimu_units.hpp:28
A multi-dimensional numeric endpoint with user customizeable range and occasional message semantics.
Definition sygah-endpoints.hpp:449
A semantically value-less endpoint that signals an event.
Definition sygah-endpoints.hpp:481
A numeric endpoint with user customizeable range and persistent value semantics.
Definition sygah-endpoints.hpp:348
Outputs of the MIMU sensor fusion component.
Definition sygsp-complementary_mimu_fusion_endpoints.hpp:73
Session data tag helper.
Definition sygah-endpoints.hpp:252
A two-state integer endpoint with persistent value semantics.
Definition sygah-endpoints.hpp:289
A MIMU data vector.
Definition sygah-mimu.hpp:40