Closed cnlohr closed 4 years ago
@nairol - any ideas?
Alan Yates recently posted some explanation what the values mean.
I'm going to use pseudo code here...
angle(axis0) = 2*PI * (sensor_hit_time/800000)
fcal.n.phase: Constant offset to every angle measurement. (Not sure if you need to add or subtract it.)
corrected_angle(axis0) = angle(axis0) + fcal.0.phase
fcal.n.tilt: Non-constant offset to every angle measurement: Offset depends on same sensor's angle in the other scan direction. (Rotation approximated by adding linear function with slope tan(tilt) )
corrected_angle(axis0) = angle(axis0) + ... + tan(fcal.0.tilt) * predicted_angle(axis1)
predicted_angle() could just be a function that adds the difference of the last 2 angle measurement to the last one.
fcal.n.curve: Could be a quadratic term? I'm guessing here...
corrected_angle(axis0) = angle(axis0) + ... + fcal.0.curve * (predicted_angle(axis1))²
fcal.n.gibphase/gibmag: Also guessing... "first Fourier term"... hmm...
corrected_angle(axis0) = angle(axis0) + .. + fcal.0.gibmag * sin(angle(axis0)+fcal.0.gibphase)
Ok, here is the final formula:
corrected_angle(axis0) = angle(axis0) + fcal.0.phase + tan(fcal.0.tilt) * predicted_angle(axis1) + fcal.0.curve * (predicted_angle(axis1))² + fcal.0.gibmag * sin(angle(axis0)+fcal.0.gibphase)
Btw. all the plus signs could as well be minus signs.
Maybe just try phase and tilt... :)
I only know the base station firmware code, that loads these values out of EEPROM and packs them into the OOTX frame. I haven't looked at the client side code that does the corrections (since that is really hard to find). I have no idea how the official software does it.
Didn't Yates also say that gibbious phase/ magnitude would better be named eccentricity? I wish I would have saved off the chat logs.
Is it possible to get precise, quantitative location values out of the production vive code? I can envision a test setup where we simulate data and send it into the vive stack either through hardware or software means and watch how different lighthouse calibration data affect the output. I.e. put in a crazy high value for tilt, and see which way everything skews. It's a brute force approach and seems like a lot of work; there may be other ways that are a lot easier.
My question on whether we can get quantitative location data out of Vive was answered in Discord. Copying here so the answer doesn't get lost: SketchStick I believe vrcmd in the steamvr stack has a pollposes option? There's a bunch of debug commands: strings vrcmd | grep '--'
I've been using the following functions in my solver and they seem to work quite nicely. I haven't tested them comprehensively, but two distinct 60 second runs converge to lighthouse positions that differ by only 1mm, whereas the uncorrected values differ by 80mm. I think the key was to treat the tilt and curve calibration parameters on the metric sensor pose, and the 0th and 1st order Fourier components on the polar angles derived from the metric pose.
// Given a predicted sensor position in the lighthouse frame, predict the perturbed measurements
template <typename T>
static void Predict(T const* params, T const* xyz, T* ang, bool correct) {
if (correct) {
ang[0] = atan2(xyz[0] - (params[0*NUM_PARAMS + PARAM_TILT] + params[0*NUM_PARAMS + PARAM_CURVE] * xyz[1]) * xyz[1], xyz[2]);
ang[1] = atan2(xyz[1] - (params[1*NUM_PARAMS + PARAM_TILT] + params[1*NUM_PARAMS + PARAM_CURVE] * xyz[0]) * xyz[0], xyz[2]);
ang[0] -= params[0*NUM_PARAMS + PARAM_PHASE] + params[0*NUM_PARAMS + PARAM_GIB_MAG] * sin(ang[0] + params[0*NUM_PARAMS + PARAM_GIB_PHASE]);
ang[1] -= params[1*NUM_PARAMS + PARAM_PHASE] + params[1*NUM_PARAMS + PARAM_GIB_MAG] * sin(ang[1] + params[1*NUM_PARAMS + PARAM_GIB_PHASE]);
} else {
ang[0] = atan2(xyz[0], xyz[2]);
ang[1] = atan2(xyz[1], xyz[2]);
}
}
// Given the perturbed lighthouse angle, predict the ideal angle
template <typename T>
static void Correct(T const* params, T * angle, bool correct) {
if (correct) {
T ideal[2], pred[2], xyz[3];
ideal[0] = angle[0];
ideal[1] = angle[1];
for (size_t i = 0; i < 10; i++) {
xyz[0] = tan(ideal[0]);
xyz[1] = tan(ideal[1]);
xyz[2] = T(1.0);
Predict(params, xyz, pred, correct);
ideal[0] += (angle[0] - pred[0]);
ideal[1] += (angle[1] - pred[1]);
}
angle[0] = ideal[0];
angle[1] = ideal[1];
}
}
@asymingt Where did you come from? Are you free to talk more about this 1:1? I.e. in discord? I don't feel I have enough understanding from your posted code to make the needed changes.
Sure. I'll idle on Discord today.
For what its worth, our current use of these parameters is detailed here:
https://github.com/cnlohr/libsurvive/wiki/BSD-Calibration-Values
and is coded up here:
https://github.com/cnlohr/libsurvive/blob/master/src/survive_reproject.c#L31
Which isn't to say that it is a solved issue; but that is whats there.
Based off of
https://github.com/nairol/LighthouseRedox/blob/master/docs/Light%20Emissions.md
and
https://github.com/nairol/LighthouseRedox/blob/master/docs/Base%20Station.md
Need to use this information to find out how the angle from center should be corrected. Right now my conversion is:
Clearly wrong. Need to find out how the fcal.0.phase, fcal.0.tilt, fcal.0.curve, fcal.0.gibphase, and fcal.0.gibmag play into it.