aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorJustin Berger <j.david.berger@gmail.com>2018-04-02 16:38:04 -0600
committerJustin Berger <j.david.berger@gmail.com>2018-04-02 16:39:11 -0600
commit0f5bf3c2f9fd7481d6b3c7c5364a08fe3ecdb2fb (patch)
tree33bf02cd36539a87148953764d79d914f13adc0f
parent83d304551bb0052f6b67365c558ea6d825585e39 (diff)
downloadlibsurvive-0f5bf3c2f9fd7481d6b3c7c5364a08fe3ecdb2fb.tar.gz
libsurvive-0f5bf3c2f9fd7481d6b3c7c5364a08fe3ecdb2fb.tar.bz2
Added documentation about writing a poser
-rw-r--r--README.md16
-rw-r--r--docs/writing_a_poser.md66
-rw-r--r--include/libsurvive/poser.h29
3 files changed, 104 insertions, 7 deletions
diff --git a/README.md b/README.md
index 4b18c43..8a28bb0 100644
--- a/README.md
+++ b/README.md
@@ -118,9 +118,10 @@ Poser | [poser_dummy.c](src/poser_dummy.c) | Template for posers | [@cnlohr](htt
Poser | [poser_octavioradii.c](src/poser_octavioradii.c) | A potentially very fast poser that works by finding the best fit of the distances from the lighthouse to each sensor that matches the known distances between sensors, given the known angles of a lighthouse sweep. Incomplete- distances appear to be found correctly, but more work needed to turn this into a pose. | [@mwturvey](https://github.com/mwturvey) and [@octavio2895](https://github.com/octavio2895)
Poser | [poser_turveytori.c](src/poser_turveytori.c) | A moderately fast, fairly high precision poser that works by determine the angle at the lighthouse between many sets of two sensors. Using the inscirbed angle theorom, each set defines a torus of possible locations of the lighthouse. Multiple sets define multiple tori, and this poser finds most likely location of the lighthouse using least-squares distance. Best suited for calibration, but is can be used for real-time tracking on a powerful system. | [@mwturvey](https://github.com/mwturvey)
Poser | [poser_epnp.c](src/poser_epnp.c) | Reasonably fast and accurate calibration and tracker that uses the [EPNP algorithm](https://en.wikipedia.org/wiki/Perspective-n-Point#EPnP) to solve the perspective and points problem. Suitable for fast tracking, but does best with >5-6 sensor readings. | [@jdavidberger](https://github.com/jdavidberger)
-Poser | [poser_sba.c](src/poser_sba.c) | Reasonably fast and accurate calibration and tracker but is dependent on a 'seed' poser to give it an initial estimate. This then performs [bundle adjustment](https://en.wikipedia.org/wiki/Bundle_adjustment) to minimize reprojection error given both ligthhouse readings. This has the benefit of greatly increasing accuracy by incorporating all the light data that is available. Set 'SBASeedPoser' config option to specify the seed poser; default is EPNP. | [@jdavidberger](https://github.com/jdavidberger)
-Disambiguator | [survive_data.c](src/survive_data.c) (currently #ifdefed out) | The old disambiguator - very fast, but slightly buggy. | [@cnlohr](https://github.com/cnlohr)
-Disambiguator | [survive_data.c](src/survive_data.c) (current disambiguator) | More complicated but much more robust disambiguator | [@mwturvey](https://github.com/mwturvey)
+Poser | [poser_sba.c](src/poser_sba.c) (default) | Reasonably fast and accurate calibration and tracker but is dependent on a 'seed' poser to give it an initial estimate. This then performs [bundle adjustment](https://en.wikipedia.org/wiki/Bundle_adjustment) to minimize reprojection error given both ligthhouse readings. This has the benefit of greatly increasing accuracy by incorporating all the light data that is available. Set 'SBASeedPoser' config option to specify the seed poser; default is EPNP. | [@jdavidberger](https://github.com/jdavidberger)
+Disambiguator | [survive_data.c](src/survive_charlesbiguator.c) | The old disambiguator - very fast, but slightly buggy. | [@cnlohr](https://github.com/cnlohr)
+Disambiguator | [survive_data.c](src/survive_turveybiguator.c) (default) | More complicated but much more robust disambiguator | [@mwturvey](https://github.com/mwturvey)
+Disambiguator | [survive_data.c](src/survive_statebased_disambiguator.c) | A fast disambiguator that was times the state shifts between pulses. Experimental. Made to allow tracking very close to the lighthouse | [@jdavidberger](https://github.com/jdavidberger)
Dismabiguator | superceded disambiguator | A more sophisticated disambiguator, development abandoned. Removed from tree. | [@jpicht](https://github.com/jpicht)
Driver | [survive_vive.c](src/survive_vive.c) | Driver for HTC Vive HMD, Watchmen (wired+wireless) and Tracker | [@cnlohr](https://github.com/cnlohr) and [@mwturvey](https://github.com/mwturvey)
OOTX Decoder | [ootx_decoder.c](src/ootx_decoder.c) | The system that takes the pulse-codes from the sync pulses from the lighthouses and get [OOTX Data](https://github.com/nairol/LighthouseRedox/blob/master/docs/Light%20Emissions.md) | [@axlecrusher](https://github.com/axlecrusher)
@@ -131,7 +132,7 @@ Component Type | Pluggability method
--- | ---
Driver | Dynamically loadable runtime, can co-exist with other drivers.
Poser | Selectable by configuration at runtime
-Disambiguator | Selectable by #define
+Disambiguator | Selectable by configuration at runtime
OOTX Decoder | Not Pluggable
@@ -146,7 +147,7 @@ To support the Vive on HDMI, you either need a newer version of HDMI, or you nee
## General Information
-The default configuration of libsurvive requires both basestations and both controllers to be active, but currently libsurvive can not make proper use of both basestations at the same time - it outputs a different pose for each basestation and does not fuse the data for one more accurate pose. This will hopefully be implemented soon. For now it's a good idea to change the configuration to only require one basestation.
+The default configuration of libsurvive requires both basestations and both controllers to be active.
Here is an example of a default configuration file that libsurvive will create as `config.json` in the current working directory when any libsurvive client is executed:
@@ -172,7 +173,7 @@ Here is an example of a default configuration file that libsurvive will create a
}
```
-To make libsurvive calibrate and run with one basestation, `lighthousecount` needs to be changed to `1`.
+To make libsurvive calibrate and run with one basestation, `lighthousecount` needs to be changed to `1`. You can also pass in `-l 1` as command line arguments.
It may be annoying to always require the controllers for calibration. To make libsurvive calibrate by using the HMD, `RequiredTrackersForCal` needs to be changed to the magic string `HMD`. The strings for the controllers are `WM0` and `WM1`, short for "Watchman". Other possible values are `WW0` (Wired Watchman) for a controller directly connected with USB or `TR0` for a Vive tracker directly connected with USB (When connected wirelessly, the tracker uses the dongles, so uses `WM0` or `WM1`).
@@ -225,6 +226,9 @@ Sometimes libsurvive goes very quickly through these steps and fills in all pose
[Here is a short demo video how successfuly running ./test should look like](https://haagch.frickel.club/Peek%202018-02-21%2023-23.webm).
+If there is already calibration data present, the library will use it. Pass `--calibrate` to force a new calibration pass.
+Conversely, if there isn't calibration data the library will auto-calibrate. Pass `--no-calibrate` to disable this calibration.
+
## Using libsurvive in your own application
Example code for libsurvive can be found in [test.c](https://github.com/cnlohr/libsurvive/blob/master/test.c). [calibrate.c](https://github.com/cnlohr/libsurvive/blob/master/calibrate.c) may contain some interesting code too.
diff --git a/docs/writing_a_poser.md b/docs/writing_a_poser.md
new file mode 100644
index 0000000..ac450e3
--- /dev/null
+++ b/docs/writing_a_poser.md
@@ -0,0 +1,66 @@
+# How to write a poser
+
+Posers in libsurvive serve two related purposes:
+
+1) If the lighthouse position isn't known, solve for them.
+2) If the lighthouse position is known, solve for the position of objects in the scene.
+
+To do this, a poser is given a variety of different signals about the current state of the input.
+
+# Registering a Poser
+
+In an effort to decouple posers from the underlying mechanics, posers are registered through a link-time
+constructor. Make a function in the following form:
+
+```
+#include "survive.h"
+
+int PoserMyPoser(SurviveObject *so, PoserData *pd) {
+ switch (pd->pt) {
+ case POSERDATA_LIGHT: {
+ PoserDataLight *lightData = (PoserDataLight *)pd;
+ return -1;
+ }
+ case POSERDATA_FULL_SCENE: {
+ PoserDataFullScene pdfs = (PoserDataFullScene *)(pd);
+ return -1;
+ }
+ case POSERDATA_IMU: {
+ PoserDataIMU *imuData = (PoserDataIMU *)pd;
+ return -1;
+ }
+ return -1;
+}
+
+REGISTER_LINKTIME(PoserMyPoser);
+
+```
+
+Note that the prefix of the function MUST be "Poser" for it to work.
+
+Now compile it into the shared object, and it will be one of the poser options available.
+
+## Input to a poser
+
+`PoserData` is a tagged union that contains the new input to the poser. See above for how to get the concrete
+types for each type of event.
+
+If you don't handle a given input, return -1. If you do, return a 0. If you have a more specific
+error number, you can return that as well.
+
+## Output from a poser
+
+To report an objects location for any one of the events above, call the function
+
+`PoserData_poser_raw_pose_func`. See the documentation in poser.h for more info.
+
+To report an initial solution to the lighthouse solution, call the function `PoserData_lighthouse_pose_func`. Again,
+see documention in poser.h
+
+## Calibration data
+
+Note that by default, no angle data is presented in a calibrated fashion. Depending on your use case, you
+may want to treat the data by grouping X, Y pairs and trying to undistort them. You can do this with the library
+function `survive_apply_bsd_calibration` from `survive_reproject.h`. Please understand though that this is, at best, an
+approximation and can be far off if the angle values are too spread out in time.
+
diff --git a/include/libsurvive/poser.h b/include/libsurvive/poser.h
index b0b1a7b..dcd0e93 100644
--- a/include/libsurvive/poser.h
+++ b/include/libsurvive/poser.h
@@ -30,9 +30,36 @@ typedef struct
void *userdata;
} PoserData;
+/**
+ * Meant to be used by individual posers to report back their findings on the pose of an object back to the invoker of
+ * the call.
+ *
+ * @param poser_data the data pointer passed into the poser function invocation
+ * @param so The survive object which we are giving a solution for.
+ * @param lighthouse @deprecated The lighthouse which observed that position. Make it -1 if it was a combination of
+ * lighthouses. Will be removed in the future.
+ * @param pose The actual object pose. This is in world space, not in LH space. It must represent a transformation from
+ * object space of the SO to global space.
+ */
void PoserData_poser_raw_pose_func(PoserData *poser_data, SurviveObject *so, uint8_t lighthouse, SurvivePose *pose);
+
+/**
+ * Meant to be used by individual posers to report back their findings on the pose of a lighthouse.
+ *
+ * Note that you are free to assume the position of the lighthouse and solve for the object or vice versa. Most solvers
+ * assume that the object is at 0,0,0 but this isn't a hard requirement.
+ *
+ * @param poser_data the data pointer passed into the poser function invocation
+ * @param so The survive object which gave us the info for the solution
+ * @param lighthouse The lighthouse which to solve for
+ * @param objUp2world For use when solving for both ligthhouse positions. For the first invocation of this function,
+ * pass in a zero-inited SurvivePose. This function will set that to a relative transform to normalize the space.
+ * pass the same pose in again for the second lighthouse to get accurate results.
+ * @param lighthouse_pose This is the assumed or derived position of the given lighthouse.
+ * @param object_pose This is the assumed or derived position of the tracked object.
+ */
void PoserData_lighthouse_pose_func(PoserData *poser_data, SurviveObject *so, uint8_t lighthouse,
- /* OUTPARAM */ SurvivePose *objUp2world, SurvivePose *lighthouse_poses,
+ /* OUTPARAM */ SurvivePose *objUp2world, SurvivePose *lighthouse_pose,
SurvivePose *object_pose);
typedef struct PoserDataIMU {