Sygaldry
Loading...
Searching...
No Matches
sygsp-complementary_mimu_fusion_endpoints.hpp
1#pragma once
2/*
3Copyright 2023 Travis J. West, Input Devices and Music Interaction Laboratory
4(IDMIL), Centre for Interdisciplinary Research in Music Media and Technology
5(CIRMMT), McGill University, Montréal, Canada, and Univ. Lille, Inria, CNRS,
6Centrale Lille, UMR 9189 CRIStAL, F-59000 Lille, France
7
8SPDX-License-Identifier: MIT
9*/
10
11#include "sygah-endpoints.hpp"
12#include "sygah-mimu.hpp"
13#include "sygsp-mimu_units.hpp"
14
15namespace sygaldry { namespace sygsp {
16
19
23
26 /* TODO:
27 - adjusting sensor alignment with device
28 - rotation of global frame into performance frame
29 - filter coefficient adjustments
30 */
31 slider<"proportional feedback"
32 , "proportional feedback gain coefficient"
33 , float, 0.0f, 10.0f, 3.0f
35 > k_P;
36 slider<"integral feedback"
37 , "integral feedback gain coefficient"
38 , float, 0.0f, 10.0f, 0.0f
40 > k_I;
41 slider<"accelerometer influence"
42 , "accelerometer gain coefficient; reflects confidence in the accelerometer data"
43 , float, 0.0f, 1.0f, 0.25f
45 > k_a;
46 slider<"magnetometer influence"
47 , "magnetometer gain coefficient; reflects confidence in the magnetometer data"
48 , float, 0.0f, 1.0f, 1.0f
50 > k_m;
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
55 > movement_threshold;
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
60 > gyro_alpha;
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;
66 //bng<"zero"
67 // , "set performance-frame alignment by rotating the performance frame "
68 // "so that its y-axis aligns with the current sensor-frame y-axis"
69 // > zero;
70};
71
74 array_message<"sensor to global quaternion", 4
75 , "quaternion representation of the orientation of the sensor in the global frame"
76 , float, -1.0f, 1.0f
77 > quaternion;
78 array_message<"global to sensor quaternion", 4
79 , "quaternion representation of the orientation of the global bases in the sensor frame"
80 , float, -1.0f, 1.0f
81 > conjugate;
82 array_message<"sensor to global matrix", 9
83 , "special orthogonal matrix of the sensor basis vectors expressed in the global frame"
84 , float, -1.0f, 1.0f
85 > matrix;
86 array_message<"global to sensor matrix", 9
87 , "special orthogonal matrix of the global basis vectors expressed in the sensor frame"
88 , float, -1.0f, 1.0f
89 > inverse;
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
92 > norm_of_gravity;
93 slider<"gravity measurements", "count of gravity measurements"
94 , unsigned int, 0, 1<<16
95 > g_count;
96 vec3_message<"sensor acceleration"
97 , float, -16.0f * mss_per_g, 16.0f * mss_per_g
98 , "m/s/s", "estimated acceleration due to motion expressed in the sensor frame of reference"
99 > sensor_accl;
100 vec3_message<"global acceleration"
101 , float, -16.0f * mss_per_g, 16.0f * mss_per_g
102 , "m/s/s", "estimated acceleration due to motion expressed in the performance frame of reference"
103 > global_accl;
104 vec3_message<"previous accelerometer"
105 , float, -16.0f, 16.0f
106 , "g", "previous measurement of acceleration; used in the estimation of jerk"
107 > accl_prev;
108 vec3_message<"jerk"
109 , float, -32.0f, 32.0f
110 , "g/s", "approximate signal analogous to the derivative of acceleration in the sensor frame"
111 > jerk;
112 vec3_message<"gyroscope bias"
113 , float, -2000.0f * rad_per_deg, 2000.0f * rad_per_deg
114 , "rad/s", "estimated gyroscope sensor bias"
115 > gyro_bias;
116 vec3_message<"magnetometer maximum"
117 , float, -4900.0f, 4900.0f
118 , "uT", "component-wise maximum of magnetometer values measured while calibrating bias compensation"
119 > magn_max;
120 vec3_message<"magnetometer minimum"
121 , float, -4900.0f, 4900.0f
122 , "uT", "component-wise minimum of magnetometer values measured while calibrating bias compensation"
123 > magn_min;
124 vec3_message<"magnetometer bias"
125 , float, -4900.0f, 4900.0f
126 , "uT", "estimated magnetometer sensor bias"
127 > magn_bias;
128 vec3_message<"angular rate"
129 , float, -2000.0f * rad_per_deg, 2000.0f * rad_per_deg
130 , "rad/s", "estimated angular rate based on fused sensor measurements"
131 > angular_rate;
132 vec3_message< "integral feedback"
133 , float, -20.0f, 20.0f
134 , "integral feedback through the complementary filter"
135 > integral_feedback;
136 toggle<"stationary"
137 , "boolean indication of whether the sensor is stationary (1) or movement is detected (0)"
138 > stationary;
139};
140
143
144} }
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
Inputs for the MIMU sensor fusion component.
Definition sygsp-complementary_mimu_fusion_endpoints.hpp:25
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