xrt: Remove old_rgb hand tracking

This commit is contained in:
Moses Turner 2023-01-26 13:23:47 -06:00
parent 10cdde859a
commit 1bba34e944
20 changed files with 14 additions and 3306 deletions

View file

@ -293,7 +293,6 @@ if(XRT_BUILD_DRIVER_HANDTRACKING)
aux_util
aux_math
t_ht_mercury
t_ht_old_rgb
hand_async
)

View file

@ -29,7 +29,6 @@
// Save me, Obi-Wan!
#include "../../tracking/hand/old_rgb/rgb_interface.h"
#include "../../tracking/hand/mercury/hg_interface.h"
#ifdef XRT_BUILD_DRIVER_DEPTHAI
@ -240,7 +239,6 @@ ht_device_create_common(struct t_stereo_camera_calibration *calib,
int
ht_device_create(struct xrt_frame_context *xfctx,
struct t_stereo_camera_calibration *calib,
enum t_hand_tracking_algorithm algorithm_choice,
struct t_camera_extra_info extra_camera_info,
struct xrt_slam_sinks **out_sinks,
struct xrt_device **out_device)
@ -251,15 +249,8 @@ ht_device_create(struct xrt_frame_context *xfctx,
struct t_hand_tracking_sync *sync = NULL;
switch (algorithm_choice) {
case HT_ALGORITHM_MERCURY: {
sync = t_hand_tracking_sync_mercury_create(calib, extra_camera_info);
} break;
case HT_ALGORITHM_OLD_RGB: {
//!@todo Either have this deal with the output space correctly, or have everything use LEFT_CAMERA
sync = t_hand_tracking_sync_old_rgb_create(calib);
}
}
sync = t_hand_tracking_sync_mercury_create(calib, extra_camera_info);
struct ht_device *htd = ht_device_create_common(calib, false, xfctx, sync);
HT_DEBUG(htd, "Hand Tracker initialized!");

View file

@ -36,7 +36,6 @@ extern "C" {
*
* @param xfctx Frame context to attach the tracker to
* @param calib Calibration struct for stereo camera
* @param algorithm_choice Which algorithm to use for hand tracking
* @param out_sinks Sinks to stream camera data to
* @param out_device Newly created hand tracker "device"
* @return int 0 on success
@ -44,7 +43,6 @@ extern "C" {
int
ht_device_create(struct xrt_frame_context *xfctx,
struct t_stereo_camera_calibration *calib,
enum t_hand_tracking_algorithm algorithm_choice,
struct t_camera_extra_info extra_camera_info,
struct xrt_slam_sinks **out_sinks,
struct xrt_device **out_device);

View file

@ -256,9 +256,8 @@ rift_s_create_hand_tracker(struct rift_s_tracker *t,
extra_camera_info.views[0].camera_orientation = CAMERA_ORIENTATION_90;
extra_camera_info.views[1].camera_orientation = CAMERA_ORIENTATION_90;
int create_status = ht_device_create(xfctx, //
t->stereo_calib, //
HT_ALGORITHM_MERCURY, //
int create_status = ht_device_create(xfctx, //
t->stereo_calib, //
extra_camera_info,
&sinks, //
&device);

View file

@ -1549,11 +1549,10 @@ wmr_hmd_hand_track(struct wmr_hmd *wh,
extra_camera_info.views[0].boundary_type = HT_IMAGE_BOUNDARY_NONE;
extra_camera_info.views[1].boundary_type = HT_IMAGE_BOUNDARY_NONE;
int create_status = ht_device_create(&wh->tracking.xfctx, //
stereo_calib, //
HT_ALGORITHM_MERCURY, //
extra_camera_info, //
&sinks, //
int create_status = ht_device_create(&wh->tracking.xfctx, //
stereo_calib, //
extra_camera_info, //
&sinks, //
&device);
if (create_status != 0) {
return create_status;

View file

@ -104,18 +104,6 @@ struct t_camera_extra_info
struct t_camera_extra_info_one_view views[2];
};
/*!
* @brief Which hand-tracking algorithm should we use?
*
* Never use HT_ALGORITHM_OLD_RGB. The tracking quality is extremely poor.
* @ingroup xrt_iface
*/
enum t_hand_tracking_algorithm
{
HT_ALGORITHM_MERCURY,
HT_ALGORITHM_OLD_RGB
};
/*!
* Synchronously processes frames and returns two hands.
*/

View file

@ -80,7 +80,6 @@ gui_scene_hand_tracking_demo(struct gui_program *p)
int create_status = ht_device_create( //
&usysd->xfctx, //
calib, //
HT_ALGORITHM_MERCURY, //
extra_camera_info, //
&hand_sinks, //
&ht_dev); //

View file

@ -59,7 +59,6 @@ DEBUG_GET_ONCE_LOG_OPTION(lh_log, "LH_LOG", U_LOGGING_WARN)
DEBUG_GET_ONCE_BOOL_OPTION(vive_over_survive, "VIVE_OVER_SURVIVE", false)
DEBUG_GET_ONCE_BOOL_OPTION(vive_slam, "VIVE_SLAM", false)
DEBUG_GET_ONCE_TRISTATE_OPTION(lh_handtracking, "LH_HANDTRACKING")
DEBUG_GET_ONCE_BOOL_OPTION(ht_use_old_rgb, "HT_USE_OLD_RGB", false)
#define LH_TRACE(...) U_LOG_IFL_T(debug_get_log_option_lh_log(), __VA_ARGS__)
#define LH_DEBUG(...) U_LOG_IFL_D(debug_get_log_option_lh_log(), __VA_ARGS__)
@ -220,13 +219,9 @@ valve_index_hand_track(struct lighthouse_system *lhs,
info.views[0].boundary.circle.normalized_radius = 0.55;
info.views[1].boundary.circle.normalized_radius = 0.55;
bool old_rgb = debug_get_bool_option_ht_use_old_rgb();
enum t_hand_tracking_algorithm ht_algorithm = old_rgb ? HT_ALGORITHM_OLD_RGB : HT_ALGORITHM_MERCURY;
struct xrt_device *ht_device = NULL;
int create_status = ht_device_create(&lhs->devices->xfctx, //
stereo_calib, //
ht_algorithm, //
info, //
&sinks, //
&ht_device);
@ -419,23 +414,13 @@ valve_index_setup_visual_trackers(struct lighthouse_system *lhs,
struct xrt_frame_sink *entry_left_sink = NULL;
struct xrt_frame_sink *entry_right_sink = NULL;
struct xrt_frame_sink *entry_sbs_sink = NULL;
bool old_rgb_ht = debug_get_bool_option_ht_use_old_rgb();
if (slam_enabled && hand_enabled && !old_rgb_ht) {
if (slam_enabled && hand_enabled) {
u_sink_split_create(&lhs->devices->xfctx, slam_sinks->left, hand_sinks->left, &entry_left_sink);
u_sink_split_create(&lhs->devices->xfctx, slam_sinks->right, hand_sinks->right, &entry_right_sink);
u_sink_stereo_sbs_to_slam_sbs_create(&lhs->devices->xfctx, entry_left_sink, entry_right_sink,
&entry_sbs_sink);
u_sink_create_format_converter(&lhs->devices->xfctx, XRT_FORMAT_L8, entry_sbs_sink, &entry_sbs_sink);
} else if (slam_enabled && hand_enabled && old_rgb_ht) {
struct xrt_frame_sink *hand_sbs = NULL;
struct xrt_frame_sink *slam_sbs = NULL;
u_sink_stereo_sbs_to_slam_sbs_create(&lhs->devices->xfctx, hand_sinks->left, hand_sinks->right,
&hand_sbs);
u_sink_stereo_sbs_to_slam_sbs_create(&lhs->devices->xfctx, slam_sinks->left, slam_sinks->right,
&slam_sbs);
u_sink_create_format_converter(&lhs->devices->xfctx, XRT_FORMAT_L8, slam_sbs, &slam_sbs);
u_sink_split_create(&lhs->devices->xfctx, slam_sbs, hand_sbs, &entry_sbs_sink);
} else if (slam_enabled) {
entry_left_sink = slam_sinks->left;
entry_right_sink = slam_sinks->right;
@ -443,12 +428,11 @@ valve_index_setup_visual_trackers(struct lighthouse_system *lhs,
&entry_sbs_sink);
u_sink_create_format_converter(&lhs->devices->xfctx, XRT_FORMAT_L8, entry_sbs_sink, &entry_sbs_sink);
} else if (hand_enabled) {
enum xrt_format fmt = old_rgb_ht ? XRT_FORMAT_R8G8B8 : XRT_FORMAT_L8;
entry_left_sink = hand_sinks->left;
entry_right_sink = hand_sinks->right;
u_sink_stereo_sbs_to_slam_sbs_create(&lhs->devices->xfctx, entry_left_sink, entry_right_sink,
&entry_sbs_sink);
u_sink_create_format_converter(&lhs->devices->xfctx, fmt, entry_sbs_sink, &entry_sbs_sink);
u_sink_create_format_converter(&lhs->devices->xfctx, XRT_FORMAT_L8, entry_sbs_sink, &entry_sbs_sink);
} else {
LH_WARN("No visual trackers were set");
return false;

View file

@ -294,11 +294,10 @@ ns_setup_depthai_device(struct ns_builder *nsb,
extra_camera_info.views[0].boundary_type = HT_IMAGE_BOUNDARY_NONE;
extra_camera_info.views[1].boundary_type = HT_IMAGE_BOUNDARY_NONE;
int create_status = ht_device_create(&usysd->xfctx, //
calib, //
HT_ALGORITHM_MERCURY, //
extra_camera_info, //
&hand_sinks, //
int create_status = ht_device_create(&usysd->xfctx, //
calib, //
extra_camera_info, //
&hand_sinks, //
out_hand_device);
t_stereo_camera_calibration_reference(&calib, NULL);
if (create_status != 0) {

View file

@ -1,7 +1,6 @@
# Copyright 2022, Collabora, Ltd.
# SPDX-License-Identifier: BSL-1.0
add_subdirectory(old_rgb)
add_subdirectory(mercury)
###

View file

@ -1,31 +0,0 @@
# Copyright 2019-2022, Collabora, Ltd.
# SPDX-License-Identifier: BSL-1.0
# Old RGB hand tracking library.
add_library(
t_ht_old_rgb STATIC
rgb_hand_math.hpp
rgb_image_math.hpp
rgb_interface.h
rgb_model.hpp
rgb_nms.hpp
rgb_sync.cpp
rgb_sync.hpp
)
target_link_libraries(
t_ht_old_rgb
PUBLIC aux-includes xrt-external-cjson
PRIVATE
aux_math
aux_tracking
aux_os
aux_util
ONNXRuntime::ONNXRuntime
${OpenCV_LIBRARIES}
)
if(XRT_HAVE_OPENCV)
target_include_directories(
t_ht_old_rgb SYSTEM PRIVATE ${OpenCV_INCLUDE_DIRS} ${EIGEN3_INCLUDE_DIR}
)
target_link_libraries(t_ht_old_rgb PUBLIC ${OpenCV_LIBRARIES})
endif()

View file

@ -1,90 +0,0 @@
<!--
Copyright 2021, Collabora, Ltd.
Authors:
Moses Turner <moses@collabora.com>
SPDX-License-Identifier: BSL-1.0
-->
# What is this?
This is a driver to do optical hand tracking. The actual code mostly written by Moses Turner, with tons of help from Marcus Edel, Jakob Bornecrantz, Ryan Pavlik, and Christoph Haag. Jakob Bornecrantz and Marcus Edel are the main people who gathered training data for the initial Collabora models.
In `main` it only works with Valve Index, although we've used a lot of Luxonis cameras in development. With additional work, it should work fine with devices like the T265, or PS4/PS5 cam, should there be enough interest for any of those.
Under good lighting, I would say it's around as good as Oculus Quest 2's hand tracking. Not that I'm trying to make any claims; that's just what I honestly would tell somebody if they are wondering if it's worth testing out.
# How to get started
## Get dependencies
### Get OpenCV
Each distro has its own way to get OpenCV, and it can change at any time; there's no specific reason to trust this documentation over anything else.
Having said that, on Ubuntu, it would look something like
```
sudo apt install libopencv-dev libopencv-contrib-dev
```
Or you could build it from source, or get it from one of the other 1000s of package managers. Whatever floats your boat.
### Get ONNXRuntime
I followed the instructions here: https://onnxruntime.ai/docs/how-to/build/inferencing.html#linux
then had to do
```
cd build/Linux/RelWithDebInfo/
sudo make install
```
### Get the ML models
Make sure you have git-lfs installed, then run ./scripts/get-ht-models.sh. Should work fine.
## Building the driver
Once onnxruntime is installed, you should be able to build like normal with CMake or Meson.
If it properly found everything, - CMake should say
```
-- Found ONNXRUNTIME: /usr/local/include/onnxruntime
[...]
-- # DRIVER_HANDTRACKING: ON
```
and Meson should say
```
Run-time dependency libonnxruntime found: YES 1.8.2
[...]
Message: Configuration done!
Message: drivers: [...] handtracking, [...]
```
## Running the driver
Currently, it's only set up to work on Valve Index.
So, the two things you can do are
* Use the `survive` driver with both controllers off - It should automagically start hand tracking upon not finding any controllers.
* Use the `vive` driver with `VIVE_USE_HANDTRACKING=ON` and it should work the same as the survive driver.
You can see if the driver is working with `openxr-simple-playground`, StereoKit, or any other app you know of. Poke me (Moses) if you find any other cool hand-tracking apps; I'm always looking for more!
# Tips and tricks
This tracking likes to be in a bright, evenly-lit room with multiple light sources. Turn all the lights on, see if you can find any lamps. If the ML models can see well, the tracking quality can get surprisingly nice.
Sometimes, the tracking fails when it can see more than one hand. As the tracking gets better (we train better ML models and squash more bugs) this should happen less often or not at all. If it does, put one of your hands down, and it should resume tracking the remaining hand just fine.
# Future improvements
* Get more training data; train better ML models.
* Improve the tracking math
* Be smarter about keeping tracking lock on a hand
* Try predicting the next bounding box based on the estimated keypoints of the last few frames instead of uncritically trusting the detection model, and not run the detection model *every single* frame.
* Instead of directly doing disparity on the observed keypoints, use a kinematic model of the hand and fit that to the 2D observations - this should get rid of a *lot* of jitter and make it look better to the end user if the ML models fail
* Make something that also works with non-stereo (mono, trinocular, or N cameras) camera setups
* Optionally run the ML models on GPU - currently, everything's CPU bound which could be sub-optimal under some circumstances
* Write a lot of generic code so that you can run this on any stereo camera
* More advanced prediction/interpolation code that doesn't care at all about the input frame cadence. One-euro filters are pretty good about this, but we can get better!

View file

@ -1,416 +0,0 @@
#pragma once
// Copyright 2021, Collabora, Ltd.
// SPDX-License-Identifier: BSL-1.0
/*!
* @file
* @brief Helper math to do things with 3D hands for the camera-based hand tracker
* @author Moses Turner <moses@collabora.com>
* @author Nick Klingensmith <programmerpichu@gmail.com>
* @ingroup drv_ht
*/
#include "math/m_api.h"
#include "math/m_vec3.h"
#include "rgb_sync.hpp"
#include "util/u_time.h"
#include "xrt/xrt_defines.h"
static constexpr int num_real_joints = 21;
float
sumOfHandJointDistances(const Hand3D &one, const Hand3D &two)
{
float dist = 0.0f;
for (int i = 0; i < num_real_joints; i++) {
dist += m_vec3_len(one.kps[i] - two.kps[i]);
}
return dist;
}
float
errHandHistory(const HandHistory3D &history_hand, const Hand3D &present_hand)
{
// Remember we never have to deal with an empty hand. Can always read the last element.
return sumOfHandJointDistances(history_hand.last_hands_unfiltered.back(), present_hand);
}
float
errHandDisparity(const Hand2D &left_rays, const Hand2D &right_rays)
{
float error_y_diff = 0.0f;
for (int i = 0; i < 21; i++) {
float diff_y = fabsf(left_rays.kps[i].y - right_rays.kps[i].y);
// Big question about what's the best loss function. Gut feeling was "I should be using sum of squared
// errors" but I don't really know. Using just sum of errors for now. Ideally it'd also be not very
// sensitive to one or two really bad outliers.
error_y_diff += diff_y;
}
// U_LOG_E("stereo camera err is %f, y_disparity is %f", err_stereo_camera, error_y_diff);
return error_y_diff;
}
void
applyThumbIndexDrag(Hand3D *hand)
{
// TERRIBLE HACK.
// Puts the thumb and pointer a bit closer together to be better at triggering XR clients' pinch detection.
static const float max_radius = 0.05;
static const float min_radius = 0.00;
// no min drag, min drag always 0.
static const float max_drag = 0.85f;
xrt_vec3 thumb = hand->kps[THMB_TIP];
xrt_vec3 index = hand->kps[INDX_TIP];
xrt_vec3 ttp = index - thumb;
float length = m_vec3_len(ttp);
if ((length > max_radius)) {
return;
}
float amount = math_map_ranges(length, min_radius, max_radius, max_drag, 0.0f);
hand->kps[THMB_TIP] = m_vec3_lerp(thumb, index, amount * 0.5f);
hand->kps[INDX_TIP] = m_vec3_lerp(index, thumb, amount * 0.5f);
}
static inline xrt_vec3
get_joint_position(struct xrt_hand_joint_set *set, xrt_hand_joint jt)
{
return set->values.hand_joint_set_default[jt].relation.pose.position;
}
template <size_t N>
static inline void
set_finger(struct xrt_hand_joint_set *set,
const xrt_vec3 &pinky_to_index_prox,
const std::array<xrt_hand_joint, N> &finger)
{
for (size_t i = 0; i < N - 1; i++) {
// Don't do fingertips. (Fingertip would be index 4.)
struct xrt_vec3 forwards =
m_vec3_normalize(get_joint_position(set, finger[i + 1]) - get_joint_position(set, finger[i]));
struct xrt_vec3 backwards = m_vec3_mul_scalar(forwards, -1.0f);
struct xrt_vec3 left = m_vec3_orthonormalize(forwards, pinky_to_index_prox);
// float dot = m_vec3_dot(backwards, left);
// assert((m_vec3_dot(backwards,left) == 0.0f));
math_quat_from_plus_x_z(&left, &backwards,
&set->values.hand_joint_set_default[finger[i]].relation.pose.orientation);
}
// Do fingertip! Per XR_EXT_hand_tracking, just copy the distal joint's orientation. Doing anything else
// is wrong.
set->values.hand_joint_set_default[finger[N - 1]].relation.pose.orientation =
set->values.hand_joint_set_default[finger[N - 2]].relation.pose.orientation;
}
void
applyJointOrientations(struct xrt_hand_joint_set *set, bool is_right)
{
// The real rule to follow is that each joint's "X" axis is along the axis along which it can bend.
// The nature of our estimation makes this a bit difficult, but these should work okay-ish under perfect
// conditions
if (set->is_active == false) {
return;
}
auto gl = [&](xrt_hand_joint jt) { return get_joint_position(set, jt); };
xrt_vec3 pinky_prox = gl(XRT_HAND_JOINT_LITTLE_PROXIMAL);
xrt_vec3 index_prox = gl(XRT_HAND_JOINT_INDEX_PROXIMAL);
xrt_vec3 pinky_to_index_prox = m_vec3_normalize(index_prox - pinky_prox);
if (is_right) {
pinky_to_index_prox = m_vec3_mul_scalar(pinky_to_index_prox, -1.0f);
}
using Finger = std::array<xrt_hand_joint, 5>;
static const std::array<Finger, 4> fingers_with_joints_in_them = {{
{XRT_HAND_JOINT_INDEX_METACARPAL, XRT_HAND_JOINT_INDEX_PROXIMAL, XRT_HAND_JOINT_INDEX_INTERMEDIATE,
XRT_HAND_JOINT_INDEX_DISTAL, XRT_HAND_JOINT_INDEX_TIP},
{XRT_HAND_JOINT_MIDDLE_METACARPAL, XRT_HAND_JOINT_MIDDLE_PROXIMAL, XRT_HAND_JOINT_MIDDLE_INTERMEDIATE,
XRT_HAND_JOINT_MIDDLE_DISTAL, XRT_HAND_JOINT_MIDDLE_TIP},
{XRT_HAND_JOINT_RING_METACARPAL, XRT_HAND_JOINT_RING_PROXIMAL, XRT_HAND_JOINT_RING_INTERMEDIATE,
XRT_HAND_JOINT_RING_DISTAL, XRT_HAND_JOINT_RING_TIP},
{XRT_HAND_JOINT_LITTLE_METACARPAL, XRT_HAND_JOINT_LITTLE_PROXIMAL, XRT_HAND_JOINT_LITTLE_INTERMEDIATE,
XRT_HAND_JOINT_LITTLE_DISTAL, XRT_HAND_JOINT_LITTLE_TIP},
}};
for (Finger const &finger : fingers_with_joints_in_them) {
set_finger(set, pinky_to_index_prox, finger);
}
// wrist!
// Not the best but acceptable. Eventually, probably, do triangle of wrist pinky prox and index prox.
set->values.hand_joint_set_default[XRT_HAND_JOINT_WRIST].relation.pose.orientation =
set->values.hand_joint_set_default[XRT_HAND_JOINT_MIDDLE_METACARPAL].relation.pose.orientation;
// palm!
set->values.hand_joint_set_default[XRT_HAND_JOINT_PALM].relation.pose.orientation =
set->values.hand_joint_set_default[XRT_HAND_JOINT_MIDDLE_METACARPAL].relation.pose.orientation;
// thumb!
// When I look at Ultraleap tracking, there's like, a "plane" made by the tip, distal and proximal (and kinda
// MCP, but least squares fitting a plane is too hard for my baby brain) Normal to this plane is the +X, and
// obviously forwards to the next joint is the -Z.
xrt_vec3 thumb_prox_to_dist = gl(XRT_HAND_JOINT_THUMB_DISTAL) - gl(XRT_HAND_JOINT_THUMB_PROXIMAL);
xrt_vec3 thumb_dist_to_tip = gl(XRT_HAND_JOINT_THUMB_TIP) - gl(XRT_HAND_JOINT_THUMB_DISTAL);
xrt_vec3 plane_normal{};
if (!is_right) {
math_vec3_cross(&thumb_prox_to_dist, &thumb_dist_to_tip, &plane_normal);
} else {
math_vec3_cross(&thumb_dist_to_tip, &thumb_prox_to_dist, &plane_normal);
}
constexpr std::array<enum xrt_hand_joint, 4> thumbs = {XRT_HAND_JOINT_THUMB_METACARPAL,
XRT_HAND_JOINT_THUMB_PROXIMAL,
XRT_HAND_JOINT_THUMB_DISTAL, XRT_HAND_JOINT_THUMB_TIP};
//! @todo this code isn't quite the same as set_finger, can we make it the same so we can use that?
for (int i = 0; i < 3; i++) {
struct xrt_vec3 backwards =
m_vec3_mul_scalar(m_vec3_normalize(gl(thumbs[i + 1]) - gl(thumbs[i])), -1.0f);
struct xrt_vec3 left = m_vec3_orthonormalize(backwards, plane_normal);
math_quat_from_plus_x_z(&left, &backwards,
&set->values.hand_joint_set_default[thumbs[i]].relation.pose.orientation);
}
struct xrt_quat *tip = &set->values.hand_joint_set_default[XRT_HAND_JOINT_THUMB_TIP].relation.pose.orientation;
struct xrt_quat *distal =
&set->values.hand_joint_set_default[XRT_HAND_JOINT_THUMB_DISTAL].relation.pose.orientation;
memcpy(tip, distal, sizeof(struct xrt_quat));
}
float
handednessJointSet(Hand3D *set)
{
// Guess if hand is left or right.
// Left is negative, right is positive.
// xrt_vec3 middle_mcp = gl(XRT_HAND_JOINT_MIDDLE_METACARPAL);
xrt_vec3 pinky_prox = set->kps[LITL_PXM]; // gl(XRT_HAND_JOINT_LITTLE_PROXIMAL);
xrt_vec3 index_prox = set->kps[INDX_PXM]; // gl(XRT_HAND_JOINT_INDEX_PROXIMAL);
xrt_vec3 pinky_to_index_prox = m_vec3_normalize(index_prox - pinky_prox);
float handedness = 0.0f;
for (int i : {INDX_PXM, MIDL_PXM, RING_PXM, LITL_PXM}) {
xrt_vec3 prox = set->kps[i];
xrt_vec3 intr = set->kps[i + 1];
xrt_vec3 dist = set->kps[i + 2];
xrt_vec3 tip = set->kps[i + 3];
xrt_vec3 prox_to_int = m_vec3_normalize(intr - prox);
xrt_vec3 int_to_dist = m_vec3_normalize(dist - intr);
xrt_vec3 dist_to_tip = m_vec3_normalize(tip - dist);
xrt_vec3 checks[2];
math_vec3_cross(&prox_to_int, &int_to_dist, &checks[0]);
math_vec3_cross(&int_to_dist, &dist_to_tip, &checks[1]);
handedness += m_vec3_dot(m_vec3_normalize(pinky_to_index_prox), (checks[0]));
handedness += m_vec3_dot(m_vec3_normalize(pinky_to_index_prox), (checks[1]));
}
set->handedness = handedness / (4 * 2);
return set->handedness;
}
void
handednessHandHistory3D(HandHistory3D *history)
{
float inter = handednessJointSet(&history->last_hands_unfiltered.back());
if ((fabsf(inter) > 0.3f) || (fabsf(history->handedness) < 0.3f)) {
history->handedness += inter;
}
static const int max_handedness = 2.0f;
if (history->handedness > max_handedness) {
history->handedness = max_handedness;
} else if (history->handedness < -max_handedness) {
history->handedness = -max_handedness;
}
}
void
handEuroFiltersInit(HandHistory3D *history, double fc_min, double fc_min_d, double beta)
{
for (int i = 0; i < 21; i++) {
m_filter_euro_vec3_init(&history->filters[i], fc_min, fc_min_d, beta);
}
}
static double
calc_smoothing_alpha(double Fc, double dt)
{
/* Calculate alpha = (1 / (1 + tau/dt)) where tau = 1.0 / (2 * pi * Fc),
* this is a straight rearrangement with fewer divisions */
double r = 2.0 * M_PI * Fc * dt;
return r / (r + 1.0);
}
static double
exp_smooth(double alpha, double y, double prev_y)
{
return alpha * y + (1.0 - alpha) * prev_y;
}
void
handEuroFiltersRun(struct HandTracking *htd, HandHistory3D *f, Hand3D *out_hand)
{
// Assume present hand is in element 0!
#if 0
// float vals[4] = {0.5, 0.33, 0.1, 0.07};
float vals[4] = {0.9, 0.09, 0.009, 0.001};
auto m = f->last_hands_unfiltered.size() - 1;
double ts_out = (vals[0] * (double)f->last_hands_unfiltered.get_at_age(std::min(m, 0))->timestamp) +
(vals[1] * (double)f->last_hands_unfiltered.get_at_age(std::min(m, 1))->timestamp) +
(vals[2] * (double)f->last_hands_unfiltered.get_at_age(std::min(m, 2))->timestamp) +
(vals[3] * (double)f->last_hands_unfiltered.get_at_age(std::min(m, 3))->timestamp);
out_hand->timestamp = (uint64_t)ts_out;
for (int kp_idx = 0; kp_idx < 21; kp_idx++) {
for (int hist_idx = 0; hist_idx < 4; hist_idx++) {
float *in_y_arr =
(float *)&f->last_hands_unfiltered.get_at_age(std::min(m, hist_idx))->kps[kp_idx];
float *out_y_arr = (float *)&out_hand->kps[kp_idx];
for (int i = 0; i < 3; i++) {
out_y_arr[i] += in_y_arr[i] * vals[hist_idx];
}
}
}
#elif 0
for (int i = 0; i < 21; i++) {
m_filter_euro_vec3_run(&f->filters[i], f->last_hands_unfiltered.back().timestamp,
&f->last_hands_unfiltered.back().kps[i], &out_hand->kps[i]);
}
// conspicuously wrong!
out_hand->timestamp = f->last_hands_unfiltered.back().timestamp;
#else
if (!f->have_prev_hand) {
f->last_hands_filtered.push_back(f->last_hands_unfiltered.back());
uint64_t ts = f->last_hands_unfiltered.back().timestamp;
f->prev_ts_for_alpha = ts;
f->first_ts = ts;
f->prev_filtered_ts = ts;
f->prev_dy = 0;
f->have_prev_hand = true;
*out_hand = f->last_hands_unfiltered.back();
}
uint64_t ts = f->last_hands_unfiltered.back().timestamp;
double dt, alpha_d;
dt = (double)(ts - f->prev_ts_for_alpha) / U_TIME_1S_IN_NS;
double abs_dy =
(sumOfHandJointDistances(f->last_hands_unfiltered.back(), f->last_hands_filtered.back()) / 21.0f) * 0.7f;
alpha_d = calc_smoothing_alpha(htd->dynamic_config.hand_fc_min_d.val, dt);
double alpha, fc_cutoff;
f->prev_dy = exp_smooth(alpha_d, abs_dy, f->prev_dy);
fc_cutoff = htd->dynamic_config.hand_fc_min.val + htd->dynamic_config.hand_beta.val * f->prev_dy;
alpha = calc_smoothing_alpha(fc_cutoff, dt);
HT_DEBUG(htd, "dt is %f, abs_dy is %f, alpha is %f", dt, abs_dy, alpha);
for (int i = 0; i < 21; i++) {
out_hand->kps[i].x =
exp_smooth(alpha, f->last_hands_unfiltered.back().kps[i].x, f->last_hands_filtered.back().kps[i].x);
out_hand->kps[i].y =
exp_smooth(alpha, f->last_hands_unfiltered.back().kps[i].y, f->last_hands_filtered.back().kps[i].y);
out_hand->kps[i].z =
exp_smooth(alpha, f->last_hands_unfiltered.back().kps[i].z, f->last_hands_filtered.back().kps[i].z);
}
double prev_ts_offset = (double)(f->prev_filtered_ts - f->first_ts);
double current_ts_offset = (double)(ts - f->first_ts);
double new_filtered_ts_offset = exp_smooth(alpha, current_ts_offset, prev_ts_offset);
uint64_t new_filtered_ts = (uint64_t)(new_filtered_ts_offset) + f->first_ts;
out_hand->timestamp = new_filtered_ts;
f->prev_filtered_ts = out_hand->timestamp;
f->prev_ts_for_alpha = ts; // NOT the filtered timestamp. NO.
#endif
}
bool
rejectTooFar(struct HandTracking *htd, Hand3D *hand)
{
static const float max_dist = 1.0f; // this sucks too - make it bigger if you can.
const float max_dist_from_camera_sqrd = max_dist * max_dist;
for (int i = 0; i < 21; i++) {
xrt_vec3 pos = hand->kps[i];
float len = m_vec3_len_sqrd(pos); // Faster.
if (len > max_dist_from_camera_sqrd) {
goto reject;
}
}
return true;
reject:
HT_TRACE(htd, "Rejected too far!");
return false;
}
bool
rejectTooClose(struct HandTracking *htd, Hand3D *hand)
{
const float min_dist = 0.12f; // Be a bit aggressive here - it's nice to not let people see our tracking fail
// when the hands are way too close
const float min_dist_from_camera_sqrd = min_dist * min_dist;
for (int i = 0; i < 21; i++) {
xrt_vec3 pos = hand->kps[i];
float len = m_vec3_len_sqrd(pos); // Faster.
if (len < min_dist_from_camera_sqrd) {
goto reject;
}
if (pos.z > min_dist) { // remember negative-Z is forward!
goto reject;
}
}
return true;
reject:
HT_TRACE(htd, "Rejected too close!");
return false;
}
bool
rejectTinyPalm(struct HandTracking *htd, Hand3D *hand)
{
// This one sucks, because some people really have tiny hands. If at some point you can stop using it, stop
// using it.
// Weird scoping so that we can still do gotos
{
float len = m_vec3_len(hand->kps[WRIST] - hand->kps[INDX_PXM]);
if ((len < 0.03f || len > 0.25f)) {
goto reject;
}
}
{
float len = m_vec3_len(hand->kps[WRIST] - hand->kps[MIDL_PXM]);
if (len < 0.03f || len > 0.25f) {
goto reject;
}
}
return true;
reject:
HT_TRACE(htd, "Rejected because too big or too small!");
return false;
}

View file

@ -1,254 +0,0 @@
// Copyright 2021, Collabora, Ltd.
// SPDX-License-Identifier: BSL-1.0
/*!
* @file
* @brief Helper math to do things with images for the camera-based hand tracker
* @author Moses Turner <moses@collabora.com>
* @ingroup drv_ht
*/
#pragma once
#include "math/m_vec2.h"
#include "math/m_vec3.h"
#include <opencv2/imgproc.hpp>
#include <opencv2/core/mat.hpp>
#include <opencv2/core/types.hpp>
/*!
* This is a template so that we can use xrt_vec3 or xrt_vec2.
* Please don't use this for anything other than xrt_vec3 or xrt_vec2!
*/
template <typename T>
T
transformVecBy2x3(T in, cv::Matx23f warp_back)
{
T rr;
rr.x = (in.x * warp_back(0, 0)) + (in.y * warp_back(0, 1)) + warp_back(0, 2);
rr.y = (in.x * warp_back(1, 0)) + (in.y * warp_back(1, 1)) + warp_back(1, 2);
return rr;
}
cv::Scalar
hsv2rgb(float fH, float fS, float fV)
{
const float fC = fV * fS; // Chroma
const float fHPrime = fmod(fH / 60.0, 6);
const float fX = fC * (1 - fabs(fmod(fHPrime, 2) - 1));
const float fM = fV - fC;
float fR, fG, fB;
if (0 <= fHPrime && fHPrime < 1) {
fR = fC;
fG = fX;
fB = 0;
} else if (1 <= fHPrime && fHPrime < 2) {
fR = fX;
fG = fC;
fB = 0;
} else if (2 <= fHPrime && fHPrime < 3) {
fR = 0;
fG = fC;
fB = fX;
} else if (3 <= fHPrime && fHPrime < 4) {
fR = 0;
fG = fX;
fB = fC;
} else if (4 <= fHPrime && fHPrime < 5) {
fR = fX;
fG = 0;
fB = fC;
} else if (5 <= fHPrime && fHPrime < 6) {
fR = fC;
fG = 0;
fB = fX;
} else {
fR = 0;
fG = 0;
fB = 0;
}
fR += fM;
fG += fM;
fB += fM;
return {fR * 255.0f, fG * 255.0f, fB * 255.0f};
}
struct xrt_vec3
raycoord(struct ht_view *htv, struct xrt_vec3 model_out)
{
cv::Mat in_px_coords(1, 1, CV_32FC2);
float *write_in;
write_in = in_px_coords.ptr<float>(0);
write_in[0] = model_out.x;
write_in[1] = model_out.y;
cv::Mat out_ray(1, 1, CV_32FC2);
cv::fisheye::undistortPoints(in_px_coords, out_ray, htv->cameraMatrix, htv->distortion);
float n_x = out_ray.at<float>(0, 0);
float n_y = out_ray.at<float>(0, 1);
struct xrt_vec3 n = {n_x, n_y, 1.0f};
cv::Matx33f R = htv->rotate_camera_to_stereo_camera;
struct xrt_vec3 o = {
(n.x * R(0, 0)) + (n.y * R(0, 1)) + (n.z * R(0, 2)),
(n.x * R(1, 0)) + (n.y * R(1, 1)) + (n.z * R(1, 2)),
(n.x * R(2, 0)) + (n.y * R(2, 1)) + (n.z * R(2, 2)),
};
math_vec3_scalar_mul(1.0f / o.z, &o);
return o;
}
cv::Matx23f
blackbar(const cv::Mat &in, cv::Mat &out, xrt_size out_size)
{
#if 1
// Easy to think about, always right, but pretty slow:
// Get a matrix from the original to the scaled down / blackbar'd image, then get one that goes back.
// Then just warpAffine() it.
// Easy in programmer time - never have to worry about off by one, special cases. We can come back and optimize
// later.
// Do the black bars need to be on top and bottom, or on left and right?
float scale_down_w = (float)out_size.w / (float)in.cols; // 128/1280 = 0.1
float scale_down_h = (float)out_size.h / (float)in.rows; // 128/800 = 0.16
float scale_down = fmin(scale_down_w, scale_down_h); // 0.1
float width_inside = (float)in.cols * scale_down;
float height_inside = (float)in.rows * scale_down;
float translate_x = (out_size.w - width_inside) / 2; // should be 0 for 1280x800
float translate_y = (out_size.h - height_inside) / 2; // should be (1280-800)/2 = 240
cv::Matx23f go;
// clang-format off
go(0,0) = scale_down; go(0,1) = 0.0f; go(0,2) = translate_x;
go(1,0) = 0.0f; go(1,1) = scale_down; go(1,2) = translate_y;
// clang-format on
cv::warpAffine(in, out, go, cv::Size(out_size.w, out_size.h));
cv::Matx23f ret;
// clang-format off
ret(0,0) = 1.0f/scale_down; ret(0,1) = 0.0f; ret(0,2) = -translate_x/scale_down;
ret(1,0) = 0.0f; ret(1,1) = 1.0f/scale_down; ret(1,2) = -translate_y/scale_down;
// clang-format on
return ret;
#else
// Fast, always wrong if the input isn't square. You'd end up using something like this, plus some
// copyMakeBorder if you want to optimize.
if (aspect_ratio_input == aspect_ratio_output) {
cv::resize(in, out, {out_size.w, out_size.h});
cv::Matx23f ret;
float scale_from_out_to_in = (float)in.cols / (float)out_size.w;
// clang-format off
ret(0,0) = scale_from_out_to_in; ret(0,1) = 0.0f; ret(0,2) = 0.0f;
ret(1,0) = 0.0f; ret(1,1) = scale_from_out_to_in; ret(1,2) = 0.0f;
// clang-format on
cv::imshow("hi", out);
cv::waitKey(1);
return ret;
}
assert(!"Uh oh! Unimplemented!");
return {};
#endif
}
void
handDot(cv::Mat &mat, xrt_vec2 place, float radius, float hue, float intensity, int type)
{
cv::circle(mat, {(int)place.x, (int)place.y}, radius, hsv2rgb(hue * 360.0f, intensity, intensity), type);
}
void
centerAndRotationFromJoints(struct ht_view *htv,
const xrt_vec2 *wrist,
const xrt_vec2 *index,
const xrt_vec2 *middle,
const xrt_vec2 *little,
xrt_vec2 *out_center,
xrt_vec2 *out_wrist_to_middle)
{
// Close to what Mediapipe does, but slightly different - just uses the middle proximal instead of "estimating"
// it from the pinky and index.
// at the end of the day I should probably do that basis vector filtering thing to get a nicer middle metacarpal
// from 6 keypoints (not thumb proximal) OR SHOULD I. because distortion. hmm
// Feel free to look at the way MP does it, you can see it's different.
// https://github.com/google/mediapipe/blob/master/mediapipe/modules/holistic_landmark/calculators/hand_detections_from_pose_to_rects_calculator.cc
// struct xrt_vec2 hand_center = m_vec2_mul_scalar(middle, 0.5) + m_vec2_mul_scalar(index, 0.5*(2.0f/3.0f)) +
// m_vec2_mul_scalar(little, 0.5f*((1.0f/3.0f))); // Middle proximal, straight-up.
// U_LOG_E("%f %f %f %f %f %f %f %f ", wrist.x, wrist.y, index.x, index.y, middle.x, middle.y, little.x,
// little.y);
*out_center = m_vec2_lerp(*middle, m_vec2_lerp(*index, *little, 1.0f / 3.0f), 0.25f);
*out_wrist_to_middle = *out_center - *wrist;
}
struct DetectionModelOutput
rotatedRectFromJoints(struct ht_view *htv, xrt_vec2 center, xrt_vec2 wrist_to_middle, DetectionModelOutput *out)
{
float box_size = m_vec2_len(wrist_to_middle) * 2.0f * 1.73f;
double rot = atan2(wrist_to_middle.x, wrist_to_middle.y) * (-180.0f / M_PI);
out->rotation = rot;
out->size = box_size;
out->center = center;
cv::RotatedRect rrect =
cv::RotatedRect(cv::Point2f(out->center.x, out->center.y), cv::Size2f(out->size, out->size), out->rotation);
cv::Point2f vertices[4];
rrect.points(vertices);
if (htv->htd->debug_scribble && htv->htd->dynamic_config.scribble_bounding_box) {
for (int i = 0; i < 4; i++) {
cv::Scalar b = cv::Scalar(10, 30, 30);
if (i == 3) {
b = cv::Scalar(255, 255, 0);
}
cv::line(htv->debug_out_to_this, vertices[i], vertices[(i + 1) % 4], b, 2);
}
}
// topright is 0. bottomright is 1. bottomleft is 2. topleft is 3.
cv::Point2f src_tri[3] = {vertices[3], vertices[2], vertices[1]}; // top-left, bottom-left, bottom-right
cv::Point2f dest_tri[3] = {cv::Point2f(0, 0), cv::Point2f(0, 224), cv::Point2f(224, 224)};
out->warp_there = getAffineTransform(src_tri, dest_tri);
out->warp_back = getAffineTransform(dest_tri, src_tri);
// out->wrist = wrist;
return *out;
}
void
planarize(const cv::Mat &input, uint8_t *output)
{
// output better be the right size, because we are not doing any bounds checking!
assert(input.isContinuous());
int lix = input.cols;
int liy = input.rows;
cv::Mat planes[3];
cv::split(input, planes);
cv::Mat red = planes[0];
cv::Mat green = planes[1];
cv::Mat blue = planes[2];
memcpy(output, red.data, lix * liy);
memcpy(output + (lix * liy), green.data, lix * liy);
memcpy(output + (lix * liy * 2), blue.data, lix * liy);
}

View file

@ -1,29 +0,0 @@
// Copyright 2022, Collabora, Ltd.
// SPDX-License-Identifier: BSL-1.0
/*!
* @file
* @brief Public interface of old rgb hand tracking.
* @author Jakob Bornecrantz <jakob@collabora.com>
* @ingroup aux_tracking
*/
#include "tracking/t_tracking.h"
#include "tracking/t_hand_tracking.h"
#ifdef __cplusplus
extern "C" {
#endif
/*!
* Create a old style RGB hand tracking pipeline.
*
* @ingroup aux_tracking
*/
struct t_hand_tracking_sync *
t_hand_tracking_sync_old_rgb_create(struct t_stereo_camera_calibration *calib);
#ifdef __cplusplus
} // extern "C"
#endif

View file

@ -1,646 +0,0 @@
// Copyright 2021, Collabora, Ltd.
// SPDX-License-Identifier: BSL-1.0
/*!
* @file
* @brief Code to run machine learning models for camera-based hand tracker.
* @author Moses Turner <moses@collabora.com>
* @author Marcus Edel <marcus.edel@collabora.com>
* @author Simon Zeni <simon@bl4ckb0ne.ca>
* @ingroup drv_ht
*/
// Many C api things were stolen from here (MIT license):
// https://github.com/microsoft/onnxruntime-inference-examples/blob/main/c_cxx/fns_candy_style_transfer/fns_candy_style_transfer.c
#pragma once
#include "rgb_sync.hpp"
#include "rgb_image_math.hpp"
#include "rgb_nms.hpp"
#include <onnxruntime_c_api.h>
#include <filesystem>
#include <array>
#undef HEAVY_SCRIBBLE
// forward-declare
struct OrtApi;
struct OrtEnv;
struct OrtMemoryInfo;
struct OrtSession;
struct OrtSessionOptions;
struct OrtValue;
namespace xrt::tracking::hand::old_rgb {
// struct ht_device;
class ht_model
{
HandTracking *device = nullptr;
const OrtApi *api = nullptr;
OrtEnv *env = nullptr;
OrtMemoryInfo *palm_detection_meminfo = nullptr;
OrtSession *palm_detection_session = nullptr;
OrtValue *palm_detection_tensor = nullptr;
std::array<float, 3 * 128 * 128> palm_detection_data;
std::mutex hand_landmark_lock;
OrtMemoryInfo *hand_landmark_meminfo = nullptr;
OrtSession *hand_landmark_session = nullptr;
OrtValue *hand_landmark_tensor = nullptr;
std::array<float, 3 * 224 * 224> hand_landmark_data;
void
init_palm_detection(OrtSessionOptions *opts);
void
init_hand_landmark(OrtSessionOptions *opts);
public:
ht_model(struct HandTracking *htd);
~ht_model();
std::vector<Palm7KP>
palm_detection(ht_view *htv, const cv::Mat &input);
Hand2D
hand_landmark(const cv::Mat input);
};
/*
* Anchors data taken from mediapipe's palm detection, used for single-shot detector model.
*
* See:
* https://google.github.io/mediapipe/solutions/hands.html#palm-detection-model
* https://github.com/google/mediapipe/blob/v0.8.8/mediapipe/calculators/tflite/ssd_anchors_calculator.cc#L101
* https://github.com/google/mediapipe/blob/v0.8.8/mediapipe/modules/palm_detection/palm_detection_cpu.pbtxt#L60
*/
struct anchor
{
float x, y;
};
static const struct anchor anchors[896]{
{0.031250, 0.031250}, {0.031250, 0.031250}, {0.093750, 0.031250}, {0.093750, 0.031250}, //
{0.156250, 0.031250}, {0.156250, 0.031250}, {0.218750, 0.031250}, {0.218750, 0.031250}, //
{0.281250, 0.031250}, {0.281250, 0.031250}, {0.343750, 0.031250}, {0.343750, 0.031250}, //
{0.406250, 0.031250}, {0.406250, 0.031250}, {0.468750, 0.031250}, {0.468750, 0.031250}, //
{0.531250, 0.031250}, {0.531250, 0.031250}, {0.593750, 0.031250}, {0.593750, 0.031250}, //
{0.656250, 0.031250}, {0.656250, 0.031250}, {0.718750, 0.031250}, {0.718750, 0.031250}, //
{0.781250, 0.031250}, {0.781250, 0.031250}, {0.843750, 0.031250}, {0.843750, 0.031250}, //
{0.906250, 0.031250}, {0.906250, 0.031250}, {0.968750, 0.031250}, {0.968750, 0.031250}, //
{0.031250, 0.093750}, {0.031250, 0.093750}, {0.093750, 0.093750}, {0.093750, 0.093750}, //
{0.156250, 0.093750}, {0.156250, 0.093750}, {0.218750, 0.093750}, {0.218750, 0.093750}, //
{0.281250, 0.093750}, {0.281250, 0.093750}, {0.343750, 0.093750}, {0.343750, 0.093750}, //
{0.406250, 0.093750}, {0.406250, 0.093750}, {0.468750, 0.093750}, {0.468750, 0.093750}, //
{0.531250, 0.093750}, {0.531250, 0.093750}, {0.593750, 0.093750}, {0.593750, 0.093750}, //
{0.656250, 0.093750}, {0.656250, 0.093750}, {0.718750, 0.093750}, {0.718750, 0.093750}, //
{0.781250, 0.093750}, {0.781250, 0.093750}, {0.843750, 0.093750}, {0.843750, 0.093750}, //
{0.906250, 0.093750}, {0.906250, 0.093750}, {0.968750, 0.093750}, {0.968750, 0.093750}, //
{0.031250, 0.156250}, {0.031250, 0.156250}, {0.093750, 0.156250}, {0.093750, 0.156250}, //
{0.156250, 0.156250}, {0.156250, 0.156250}, {0.218750, 0.156250}, {0.218750, 0.156250}, //
{0.281250, 0.156250}, {0.281250, 0.156250}, {0.343750, 0.156250}, {0.343750, 0.156250}, //
{0.406250, 0.156250}, {0.406250, 0.156250}, {0.468750, 0.156250}, {0.468750, 0.156250}, //
{0.531250, 0.156250}, {0.531250, 0.156250}, {0.593750, 0.156250}, {0.593750, 0.156250}, //
{0.656250, 0.156250}, {0.656250, 0.156250}, {0.718750, 0.156250}, {0.718750, 0.156250}, //
{0.781250, 0.156250}, {0.781250, 0.156250}, {0.843750, 0.156250}, {0.843750, 0.156250}, //
{0.906250, 0.156250}, {0.906250, 0.156250}, {0.968750, 0.156250}, {0.968750, 0.156250}, //
{0.031250, 0.218750}, {0.031250, 0.218750}, {0.093750, 0.218750}, {0.093750, 0.218750}, //
{0.156250, 0.218750}, {0.156250, 0.218750}, {0.218750, 0.218750}, {0.218750, 0.218750}, //
{0.281250, 0.218750}, {0.281250, 0.218750}, {0.343750, 0.218750}, {0.343750, 0.218750}, //
{0.406250, 0.218750}, {0.406250, 0.218750}, {0.468750, 0.218750}, {0.468750, 0.218750}, //
{0.531250, 0.218750}, {0.531250, 0.218750}, {0.593750, 0.218750}, {0.593750, 0.218750}, //
{0.656250, 0.218750}, {0.656250, 0.218750}, {0.718750, 0.218750}, {0.718750, 0.218750}, //
{0.781250, 0.218750}, {0.781250, 0.218750}, {0.843750, 0.218750}, {0.843750, 0.218750}, //
{0.906250, 0.218750}, {0.906250, 0.218750}, {0.968750, 0.218750}, {0.968750, 0.218750}, //
{0.031250, 0.281250}, {0.031250, 0.281250}, {0.093750, 0.281250}, {0.093750, 0.281250}, //
{0.156250, 0.281250}, {0.156250, 0.281250}, {0.218750, 0.281250}, {0.218750, 0.281250}, //
{0.281250, 0.281250}, {0.281250, 0.281250}, {0.343750, 0.281250}, {0.343750, 0.281250}, //
{0.406250, 0.281250}, {0.406250, 0.281250}, {0.468750, 0.281250}, {0.468750, 0.281250}, //
{0.531250, 0.281250}, {0.531250, 0.281250}, {0.593750, 0.281250}, {0.593750, 0.281250}, //
{0.656250, 0.281250}, {0.656250, 0.281250}, {0.718750, 0.281250}, {0.718750, 0.281250}, //
{0.781250, 0.281250}, {0.781250, 0.281250}, {0.843750, 0.281250}, {0.843750, 0.281250}, //
{0.906250, 0.281250}, {0.906250, 0.281250}, {0.968750, 0.281250}, {0.968750, 0.281250}, //
{0.031250, 0.343750}, {0.031250, 0.343750}, {0.093750, 0.343750}, {0.093750, 0.343750}, //
{0.156250, 0.343750}, {0.156250, 0.343750}, {0.218750, 0.343750}, {0.218750, 0.343750}, //
{0.281250, 0.343750}, {0.281250, 0.343750}, {0.343750, 0.343750}, {0.343750, 0.343750}, //
{0.406250, 0.343750}, {0.406250, 0.343750}, {0.468750, 0.343750}, {0.468750, 0.343750}, //
{0.531250, 0.343750}, {0.531250, 0.343750}, {0.593750, 0.343750}, {0.593750, 0.343750}, //
{0.656250, 0.343750}, {0.656250, 0.343750}, {0.718750, 0.343750}, {0.718750, 0.343750}, //
{0.781250, 0.343750}, {0.781250, 0.343750}, {0.843750, 0.343750}, {0.843750, 0.343750}, //
{0.906250, 0.343750}, {0.906250, 0.343750}, {0.968750, 0.343750}, {0.968750, 0.343750}, //
{0.031250, 0.406250}, {0.031250, 0.406250}, {0.093750, 0.406250}, {0.093750, 0.406250}, //
{0.156250, 0.406250}, {0.156250, 0.406250}, {0.218750, 0.406250}, {0.218750, 0.406250}, //
{0.281250, 0.406250}, {0.281250, 0.406250}, {0.343750, 0.406250}, {0.343750, 0.406250}, //
{0.406250, 0.406250}, {0.406250, 0.406250}, {0.468750, 0.406250}, {0.468750, 0.406250}, //
{0.531250, 0.406250}, {0.531250, 0.406250}, {0.593750, 0.406250}, {0.593750, 0.406250}, //
{0.656250, 0.406250}, {0.656250, 0.406250}, {0.718750, 0.406250}, {0.718750, 0.406250}, //
{0.781250, 0.406250}, {0.781250, 0.406250}, {0.843750, 0.406250}, {0.843750, 0.406250}, //
{0.906250, 0.406250}, {0.906250, 0.406250}, {0.968750, 0.406250}, {0.968750, 0.406250}, //
{0.031250, 0.468750}, {0.031250, 0.468750}, {0.093750, 0.468750}, {0.093750, 0.468750}, //
{0.156250, 0.468750}, {0.156250, 0.468750}, {0.218750, 0.468750}, {0.218750, 0.468750}, //
{0.281250, 0.468750}, {0.281250, 0.468750}, {0.343750, 0.468750}, {0.343750, 0.468750}, //
{0.406250, 0.468750}, {0.406250, 0.468750}, {0.468750, 0.468750}, {0.468750, 0.468750}, //
{0.531250, 0.468750}, {0.531250, 0.468750}, {0.593750, 0.468750}, {0.593750, 0.468750}, //
{0.656250, 0.468750}, {0.656250, 0.468750}, {0.718750, 0.468750}, {0.718750, 0.468750}, //
{0.781250, 0.468750}, {0.781250, 0.468750}, {0.843750, 0.468750}, {0.843750, 0.468750}, //
{0.906250, 0.468750}, {0.906250, 0.468750}, {0.968750, 0.468750}, {0.968750, 0.468750}, //
{0.031250, 0.531250}, {0.031250, 0.531250}, {0.093750, 0.531250}, {0.093750, 0.531250}, //
{0.156250, 0.531250}, {0.156250, 0.531250}, {0.218750, 0.531250}, {0.218750, 0.531250}, //
{0.281250, 0.531250}, {0.281250, 0.531250}, {0.343750, 0.531250}, {0.343750, 0.531250}, //
{0.406250, 0.531250}, {0.406250, 0.531250}, {0.468750, 0.531250}, {0.468750, 0.531250}, //
{0.531250, 0.531250}, {0.531250, 0.531250}, {0.593750, 0.531250}, {0.593750, 0.531250}, //
{0.656250, 0.531250}, {0.656250, 0.531250}, {0.718750, 0.531250}, {0.718750, 0.531250}, //
{0.781250, 0.531250}, {0.781250, 0.531250}, {0.843750, 0.531250}, {0.843750, 0.531250}, //
{0.906250, 0.531250}, {0.906250, 0.531250}, {0.968750, 0.531250}, {0.968750, 0.531250}, //
{0.031250, 0.593750}, {0.031250, 0.593750}, {0.093750, 0.593750}, {0.093750, 0.593750}, //
{0.156250, 0.593750}, {0.156250, 0.593750}, {0.218750, 0.593750}, {0.218750, 0.593750}, //
{0.281250, 0.593750}, {0.281250, 0.593750}, {0.343750, 0.593750}, {0.343750, 0.593750}, //
{0.406250, 0.593750}, {0.406250, 0.593750}, {0.468750, 0.593750}, {0.468750, 0.593750}, //
{0.531250, 0.593750}, {0.531250, 0.593750}, {0.593750, 0.593750}, {0.593750, 0.593750}, //
{0.656250, 0.593750}, {0.656250, 0.593750}, {0.718750, 0.593750}, {0.718750, 0.593750}, //
{0.781250, 0.593750}, {0.781250, 0.593750}, {0.843750, 0.593750}, {0.843750, 0.593750}, //
{0.906250, 0.593750}, {0.906250, 0.593750}, {0.968750, 0.593750}, {0.968750, 0.593750}, //
{0.031250, 0.656250}, {0.031250, 0.656250}, {0.093750, 0.656250}, {0.093750, 0.656250}, //
{0.156250, 0.656250}, {0.156250, 0.656250}, {0.218750, 0.656250}, {0.218750, 0.656250}, //
{0.281250, 0.656250}, {0.281250, 0.656250}, {0.343750, 0.656250}, {0.343750, 0.656250}, //
{0.406250, 0.656250}, {0.406250, 0.656250}, {0.468750, 0.656250}, {0.468750, 0.656250}, //
{0.531250, 0.656250}, {0.531250, 0.656250}, {0.593750, 0.656250}, {0.593750, 0.656250}, //
{0.656250, 0.656250}, {0.656250, 0.656250}, {0.718750, 0.656250}, {0.718750, 0.656250}, //
{0.781250, 0.656250}, {0.781250, 0.656250}, {0.843750, 0.656250}, {0.843750, 0.656250}, //
{0.906250, 0.656250}, {0.906250, 0.656250}, {0.968750, 0.656250}, {0.968750, 0.656250}, //
{0.031250, 0.718750}, {0.031250, 0.718750}, {0.093750, 0.718750}, {0.093750, 0.718750}, //
{0.156250, 0.718750}, {0.156250, 0.718750}, {0.218750, 0.718750}, {0.218750, 0.718750}, //
{0.281250, 0.718750}, {0.281250, 0.718750}, {0.343750, 0.718750}, {0.343750, 0.718750}, //
{0.406250, 0.718750}, {0.406250, 0.718750}, {0.468750, 0.718750}, {0.468750, 0.718750}, //
{0.531250, 0.718750}, {0.531250, 0.718750}, {0.593750, 0.718750}, {0.593750, 0.718750}, //
{0.656250, 0.718750}, {0.656250, 0.718750}, {0.718750, 0.718750}, {0.718750, 0.718750}, //
{0.781250, 0.718750}, {0.781250, 0.718750}, {0.843750, 0.718750}, {0.843750, 0.718750}, //
{0.906250, 0.718750}, {0.906250, 0.718750}, {0.968750, 0.718750}, {0.968750, 0.718750}, //
{0.031250, 0.781250}, {0.031250, 0.781250}, {0.093750, 0.781250}, {0.093750, 0.781250}, //
{0.156250, 0.781250}, {0.156250, 0.781250}, {0.218750, 0.781250}, {0.218750, 0.781250}, //
{0.281250, 0.781250}, {0.281250, 0.781250}, {0.343750, 0.781250}, {0.343750, 0.781250}, //
{0.406250, 0.781250}, {0.406250, 0.781250}, {0.468750, 0.781250}, {0.468750, 0.781250}, //
{0.531250, 0.781250}, {0.531250, 0.781250}, {0.593750, 0.781250}, {0.593750, 0.781250}, //
{0.656250, 0.781250}, {0.656250, 0.781250}, {0.718750, 0.781250}, {0.718750, 0.781250}, //
{0.781250, 0.781250}, {0.781250, 0.781250}, {0.843750, 0.781250}, {0.843750, 0.781250}, //
{0.906250, 0.781250}, {0.906250, 0.781250}, {0.968750, 0.781250}, {0.968750, 0.781250}, //
{0.031250, 0.843750}, {0.031250, 0.843750}, {0.093750, 0.843750}, {0.093750, 0.843750}, //
{0.156250, 0.843750}, {0.156250, 0.843750}, {0.218750, 0.843750}, {0.218750, 0.843750}, //
{0.281250, 0.843750}, {0.281250, 0.843750}, {0.343750, 0.843750}, {0.343750, 0.843750}, //
{0.406250, 0.843750}, {0.406250, 0.843750}, {0.468750, 0.843750}, {0.468750, 0.843750}, //
{0.531250, 0.843750}, {0.531250, 0.843750}, {0.593750, 0.843750}, {0.593750, 0.843750}, //
{0.656250, 0.843750}, {0.656250, 0.843750}, {0.718750, 0.843750}, {0.718750, 0.843750}, //
{0.781250, 0.843750}, {0.781250, 0.843750}, {0.843750, 0.843750}, {0.843750, 0.843750}, //
{0.906250, 0.843750}, {0.906250, 0.843750}, {0.968750, 0.843750}, {0.968750, 0.843750}, //
{0.031250, 0.906250}, {0.031250, 0.906250}, {0.093750, 0.906250}, {0.093750, 0.906250}, //
{0.156250, 0.906250}, {0.156250, 0.906250}, {0.218750, 0.906250}, {0.218750, 0.906250}, //
{0.281250, 0.906250}, {0.281250, 0.906250}, {0.343750, 0.906250}, {0.343750, 0.906250}, //
{0.406250, 0.906250}, {0.406250, 0.906250}, {0.468750, 0.906250}, {0.468750, 0.906250}, //
{0.531250, 0.906250}, {0.531250, 0.906250}, {0.593750, 0.906250}, {0.593750, 0.906250}, //
{0.656250, 0.906250}, {0.656250, 0.906250}, {0.718750, 0.906250}, {0.718750, 0.906250}, //
{0.781250, 0.906250}, {0.781250, 0.906250}, {0.843750, 0.906250}, {0.843750, 0.906250}, //
{0.906250, 0.906250}, {0.906250, 0.906250}, {0.968750, 0.906250}, {0.968750, 0.906250}, //
{0.031250, 0.968750}, {0.031250, 0.968750}, {0.093750, 0.968750}, {0.093750, 0.968750}, //
{0.156250, 0.968750}, {0.156250, 0.968750}, {0.218750, 0.968750}, {0.218750, 0.968750}, //
{0.281250, 0.968750}, {0.281250, 0.968750}, {0.343750, 0.968750}, {0.343750, 0.968750}, //
{0.406250, 0.968750}, {0.406250, 0.968750}, {0.468750, 0.968750}, {0.468750, 0.968750}, //
{0.531250, 0.968750}, {0.531250, 0.968750}, {0.593750, 0.968750}, {0.593750, 0.968750}, //
{0.656250, 0.968750}, {0.656250, 0.968750}, {0.718750, 0.968750}, {0.718750, 0.968750}, //
{0.781250, 0.968750}, {0.781250, 0.968750}, {0.843750, 0.968750}, {0.843750, 0.968750}, //
{0.906250, 0.968750}, {0.906250, 0.968750}, {0.968750, 0.968750}, {0.968750, 0.968750}, //
{0.062500, 0.062500}, {0.062500, 0.062500}, {0.062500, 0.062500}, {0.062500, 0.062500}, //
{0.062500, 0.062500}, {0.062500, 0.062500}, {0.187500, 0.062500}, {0.187500, 0.062500}, //
{0.187500, 0.062500}, {0.187500, 0.062500}, {0.187500, 0.062500}, {0.187500, 0.062500}, //
{0.312500, 0.062500}, {0.312500, 0.062500}, {0.312500, 0.062500}, {0.312500, 0.062500}, //
{0.312500, 0.062500}, {0.312500, 0.062500}, {0.437500, 0.062500}, {0.437500, 0.062500}, //
{0.437500, 0.062500}, {0.437500, 0.062500}, {0.437500, 0.062500}, {0.437500, 0.062500}, //
{0.562500, 0.062500}, {0.562500, 0.062500}, {0.562500, 0.062500}, {0.562500, 0.062500}, //
{0.562500, 0.062500}, {0.562500, 0.062500}, {0.687500, 0.062500}, {0.687500, 0.062500}, //
{0.687500, 0.062500}, {0.687500, 0.062500}, {0.687500, 0.062500}, {0.687500, 0.062500}, //
{0.812500, 0.062500}, {0.812500, 0.062500}, {0.812500, 0.062500}, {0.812500, 0.062500}, //
{0.812500, 0.062500}, {0.812500, 0.062500}, {0.937500, 0.062500}, {0.937500, 0.062500}, //
{0.937500, 0.062500}, {0.937500, 0.062500}, {0.937500, 0.062500}, {0.937500, 0.062500}, //
{0.062500, 0.187500}, {0.062500, 0.187500}, {0.062500, 0.187500}, {0.062500, 0.187500}, //
{0.062500, 0.187500}, {0.062500, 0.187500}, {0.187500, 0.187500}, {0.187500, 0.187500}, //
{0.187500, 0.187500}, {0.187500, 0.187500}, {0.187500, 0.187500}, {0.187500, 0.187500}, //
{0.312500, 0.187500}, {0.312500, 0.187500}, {0.312500, 0.187500}, {0.312500, 0.187500}, //
{0.312500, 0.187500}, {0.312500, 0.187500}, {0.437500, 0.187500}, {0.437500, 0.187500}, //
{0.437500, 0.187500}, {0.437500, 0.187500}, {0.437500, 0.187500}, {0.437500, 0.187500}, //
{0.562500, 0.187500}, {0.562500, 0.187500}, {0.562500, 0.187500}, {0.562500, 0.187500}, //
{0.562500, 0.187500}, {0.562500, 0.187500}, {0.687500, 0.187500}, {0.687500, 0.187500}, //
{0.687500, 0.187500}, {0.687500, 0.187500}, {0.687500, 0.187500}, {0.687500, 0.187500}, //
{0.812500, 0.187500}, {0.812500, 0.187500}, {0.812500, 0.187500}, {0.812500, 0.187500}, //
{0.812500, 0.187500}, {0.812500, 0.187500}, {0.937500, 0.187500}, {0.937500, 0.187500}, //
{0.937500, 0.187500}, {0.937500, 0.187500}, {0.937500, 0.187500}, {0.937500, 0.187500}, //
{0.062500, 0.312500}, {0.062500, 0.312500}, {0.062500, 0.312500}, {0.062500, 0.312500}, //
{0.062500, 0.312500}, {0.062500, 0.312500}, {0.187500, 0.312500}, {0.187500, 0.312500}, //
{0.187500, 0.312500}, {0.187500, 0.312500}, {0.187500, 0.312500}, {0.187500, 0.312500}, //
{0.312500, 0.312500}, {0.312500, 0.312500}, {0.312500, 0.312500}, {0.312500, 0.312500}, //
{0.312500, 0.312500}, {0.312500, 0.312500}, {0.437500, 0.312500}, {0.437500, 0.312500}, //
{0.437500, 0.312500}, {0.437500, 0.312500}, {0.437500, 0.312500}, {0.437500, 0.312500}, //
{0.562500, 0.312500}, {0.562500, 0.312500}, {0.562500, 0.312500}, {0.562500, 0.312500}, //
{0.562500, 0.312500}, {0.562500, 0.312500}, {0.687500, 0.312500}, {0.687500, 0.312500}, //
{0.687500, 0.312500}, {0.687500, 0.312500}, {0.687500, 0.312500}, {0.687500, 0.312500}, //
{0.812500, 0.312500}, {0.812500, 0.312500}, {0.812500, 0.312500}, {0.812500, 0.312500}, //
{0.812500, 0.312500}, {0.812500, 0.312500}, {0.937500, 0.312500}, {0.937500, 0.312500}, //
{0.937500, 0.312500}, {0.937500, 0.312500}, {0.937500, 0.312500}, {0.937500, 0.312500}, //
{0.062500, 0.437500}, {0.062500, 0.437500}, {0.062500, 0.437500}, {0.062500, 0.437500}, //
{0.062500, 0.437500}, {0.062500, 0.437500}, {0.187500, 0.437500}, {0.187500, 0.437500}, //
{0.187500, 0.437500}, {0.187500, 0.437500}, {0.187500, 0.437500}, {0.187500, 0.437500}, //
{0.312500, 0.437500}, {0.312500, 0.437500}, {0.312500, 0.437500}, {0.312500, 0.437500}, //
{0.312500, 0.437500}, {0.312500, 0.437500}, {0.437500, 0.437500}, {0.437500, 0.437500}, //
{0.437500, 0.437500}, {0.437500, 0.437500}, {0.437500, 0.437500}, {0.437500, 0.437500}, //
{0.562500, 0.437500}, {0.562500, 0.437500}, {0.562500, 0.437500}, {0.562500, 0.437500}, //
{0.562500, 0.437500}, {0.562500, 0.437500}, {0.687500, 0.437500}, {0.687500, 0.437500}, //
{0.687500, 0.437500}, {0.687500, 0.437500}, {0.687500, 0.437500}, {0.687500, 0.437500}, //
{0.812500, 0.437500}, {0.812500, 0.437500}, {0.812500, 0.437500}, {0.812500, 0.437500}, //
{0.812500, 0.437500}, {0.812500, 0.437500}, {0.937500, 0.437500}, {0.937500, 0.437500}, //
{0.937500, 0.437500}, {0.937500, 0.437500}, {0.937500, 0.437500}, {0.937500, 0.437500}, //
{0.062500, 0.562500}, {0.062500, 0.562500}, {0.062500, 0.562500}, {0.062500, 0.562500}, //
{0.062500, 0.562500}, {0.062500, 0.562500}, {0.187500, 0.562500}, {0.187500, 0.562500}, //
{0.187500, 0.562500}, {0.187500, 0.562500}, {0.187500, 0.562500}, {0.187500, 0.562500}, //
{0.312500, 0.562500}, {0.312500, 0.562500}, {0.312500, 0.562500}, {0.312500, 0.562500}, //
{0.312500, 0.562500}, {0.312500, 0.562500}, {0.437500, 0.562500}, {0.437500, 0.562500}, //
{0.437500, 0.562500}, {0.437500, 0.562500}, {0.437500, 0.562500}, {0.437500, 0.562500}, //
{0.562500, 0.562500}, {0.562500, 0.562500}, {0.562500, 0.562500}, {0.562500, 0.562500}, //
{0.562500, 0.562500}, {0.562500, 0.562500}, {0.687500, 0.562500}, {0.687500, 0.562500}, //
{0.687500, 0.562500}, {0.687500, 0.562500}, {0.687500, 0.562500}, {0.687500, 0.562500}, //
{0.812500, 0.562500}, {0.812500, 0.562500}, {0.812500, 0.562500}, {0.812500, 0.562500}, //
{0.812500, 0.562500}, {0.812500, 0.562500}, {0.937500, 0.562500}, {0.937500, 0.562500}, //
{0.937500, 0.562500}, {0.937500, 0.562500}, {0.937500, 0.562500}, {0.937500, 0.562500}, //
{0.062500, 0.687500}, {0.062500, 0.687500}, {0.062500, 0.687500}, {0.062500, 0.687500}, //
{0.062500, 0.687500}, {0.062500, 0.687500}, {0.187500, 0.687500}, {0.187500, 0.687500}, //
{0.187500, 0.687500}, {0.187500, 0.687500}, {0.187500, 0.687500}, {0.187500, 0.687500}, //
{0.312500, 0.687500}, {0.312500, 0.687500}, {0.312500, 0.687500}, {0.312500, 0.687500}, //
{0.312500, 0.687500}, {0.312500, 0.687500}, {0.437500, 0.687500}, {0.437500, 0.687500}, //
{0.437500, 0.687500}, {0.437500, 0.687500}, {0.437500, 0.687500}, {0.437500, 0.687500}, //
{0.562500, 0.687500}, {0.562500, 0.687500}, {0.562500, 0.687500}, {0.562500, 0.687500}, //
{0.562500, 0.687500}, {0.562500, 0.687500}, {0.687500, 0.687500}, {0.687500, 0.687500}, //
{0.687500, 0.687500}, {0.687500, 0.687500}, {0.687500, 0.687500}, {0.687500, 0.687500}, //
{0.812500, 0.687500}, {0.812500, 0.687500}, {0.812500, 0.687500}, {0.812500, 0.687500}, //
{0.812500, 0.687500}, {0.812500, 0.687500}, {0.937500, 0.687500}, {0.937500, 0.687500}, //
{0.937500, 0.687500}, {0.937500, 0.687500}, {0.937500, 0.687500}, {0.937500, 0.687500}, //
{0.062500, 0.812500}, {0.062500, 0.812500}, {0.062500, 0.812500}, {0.062500, 0.812500}, //
{0.062500, 0.812500}, {0.062500, 0.812500}, {0.187500, 0.812500}, {0.187500, 0.812500}, //
{0.187500, 0.812500}, {0.187500, 0.812500}, {0.187500, 0.812500}, {0.187500, 0.812500}, //
{0.312500, 0.812500}, {0.312500, 0.812500}, {0.312500, 0.812500}, {0.312500, 0.812500}, //
{0.312500, 0.812500}, {0.312500, 0.812500}, {0.437500, 0.812500}, {0.437500, 0.812500}, //
{0.437500, 0.812500}, {0.437500, 0.812500}, {0.437500, 0.812500}, {0.437500, 0.812500}, //
{0.562500, 0.812500}, {0.562500, 0.812500}, {0.562500, 0.812500}, {0.562500, 0.812500}, //
{0.562500, 0.812500}, {0.562500, 0.812500}, {0.687500, 0.812500}, {0.687500, 0.812500}, //
{0.687500, 0.812500}, {0.687500, 0.812500}, {0.687500, 0.812500}, {0.687500, 0.812500}, //
{0.812500, 0.812500}, {0.812500, 0.812500}, {0.812500, 0.812500}, {0.812500, 0.812500}, //
{0.812500, 0.812500}, {0.812500, 0.812500}, {0.937500, 0.812500}, {0.937500, 0.812500}, //
{0.937500, 0.812500}, {0.937500, 0.812500}, {0.937500, 0.812500}, {0.937500, 0.812500}, //
{0.062500, 0.937500}, {0.062500, 0.937500}, {0.062500, 0.937500}, {0.062500, 0.937500}, //
{0.062500, 0.937500}, {0.062500, 0.937500}, {0.187500, 0.937500}, {0.187500, 0.937500}, //
{0.187500, 0.937500}, {0.187500, 0.937500}, {0.187500, 0.937500}, {0.187500, 0.937500}, //
{0.312500, 0.937500}, {0.312500, 0.937500}, {0.312500, 0.937500}, {0.312500, 0.937500}, //
{0.312500, 0.937500}, {0.312500, 0.937500}, {0.437500, 0.937500}, {0.437500, 0.937500}, //
{0.437500, 0.937500}, {0.437500, 0.937500}, {0.437500, 0.937500}, {0.437500, 0.937500}, //
{0.562500, 0.937500}, {0.562500, 0.937500}, {0.562500, 0.937500}, {0.562500, 0.937500}, //
{0.562500, 0.937500}, {0.562500, 0.937500}, {0.687500, 0.937500}, {0.687500, 0.937500}, //
{0.687500, 0.937500}, {0.687500, 0.937500}, {0.687500, 0.937500}, {0.687500, 0.937500}, //
{0.812500, 0.937500}, {0.812500, 0.937500}, {0.812500, 0.937500}, {0.812500, 0.937500}, //
{0.812500, 0.937500}, {0.812500, 0.937500}, {0.937500, 0.937500}, {0.937500, 0.937500}, //
{0.937500, 0.937500}, {0.937500, 0.937500}, {0.937500, 0.937500}, {0.937500, 0.937500}, //
};
#define ORT(expr) \
do { \
OrtStatus *status = this->api->expr; \
if (status != nullptr) { \
const char *msg = this->api->GetErrorMessage(status); \
HT_ERROR(this->device, "[%s:%d]: %s\n", __FILE__, __LINE__, msg); \
this->api->ReleaseStatus(status); \
assert(false); \
} \
} while (0)
void
ht_model::init_palm_detection(OrtSessionOptions *opts)
{
// Both models have slightly different shapes, preventing us to constexpr the input shape
std::array<int64_t, 4> input_shape;
std::array<std::string, 1> input_names;
std::filesystem::path path = this->device->startup_config.model_slug;
if (this->device->startup_config.keypoint_estimation_use_mediapipe) {
path /= "palm_detection_MEDIAPIPE.onnx";
input_shape = {1, 3, 128, 128};
input_names = {"input"};
} else {
path /= "palm_detection_COLLABORA.onnx";
input_shape = {1, 128, 128, 3};
input_names = {"input:0"};
}
HT_DEBUG(this->device, "Loading palm detection model from file '%s'", path.c_str());
ORT(CreateSession(this->env, path.c_str(), opts, &this->palm_detection_session));
assert(this->palm_detection_session);
constexpr size_t input_size = 3 * 128 * 128;
ORT(CreateTensorWithDataAsOrtValue(this->palm_detection_meminfo, this->palm_detection_data.data(),
input_size * sizeof(float), input_shape.data(), input_shape.size(),
ONNX_TENSOR_ELEMENT_DATA_TYPE_FLOAT, &this->palm_detection_tensor));
assert(this->palm_detection_tensor);
int is_tensor;
ORT(IsTensor(this->palm_detection_tensor, &is_tensor));
assert(is_tensor);
}
void
ht_model::init_hand_landmark(OrtSessionOptions *opts)
{
std::filesystem::path path = this->device->startup_config.model_slug;
if (this->device->startup_config.keypoint_estimation_use_mediapipe) {
path /= "hand_landmark_MEDIAPIPE.onnx";
} else {
path /= "hand_landmark_COLLABORA.onnx";
}
HT_DEBUG(this->device, "Loading hand landmark model from file '%s'", path.c_str());
ORT(CreateSession(this->env, path.c_str(), opts, &this->hand_landmark_session));
assert(this->hand_landmark_session);
constexpr size_t input_size = 3 * 224 * 224;
constexpr std::array<int64_t, 4> input_shape = {1, 3, 224, 224};
ORT(CreateTensorWithDataAsOrtValue(this->hand_landmark_meminfo, this->hand_landmark_data.data(),
input_size * sizeof(float), input_shape.data(), input_shape.size(),
ONNX_TENSOR_ELEMENT_DATA_TYPE_FLOAT, &this->hand_landmark_tensor));
assert(this->hand_landmark_tensor != nullptr);
int is_tensor;
ORT(IsTensor(hand_landmark_tensor, &is_tensor));
assert(is_tensor);
}
ht_model::ht_model(struct HandTracking *htd) : device(htd), api(OrtGetApiBase()->GetApi(ORT_API_VERSION))
{
ORT(CreateEnv(ORT_LOGGING_LEVEL_WARNING, "monado_ht", &this->env));
ORT(CreateCpuMemoryInfo(OrtArenaAllocator, OrtMemTypeDefault, &this->palm_detection_meminfo));
ORT(CreateCpuMemoryInfo(OrtArenaAllocator, OrtMemTypeDefault, &this->hand_landmark_meminfo));
OrtSessionOptions *opts = nullptr;
ORT(CreateSessionOptions(&opts));
// TODO review options, config for threads?
ORT(SetSessionGraphOptimizationLevel(opts, ORT_ENABLE_ALL));
ORT(SetIntraOpNumThreads(opts, 1));
this->init_palm_detection(opts);
this->init_hand_landmark(opts);
this->api->ReleaseSessionOptions(opts);
}
ht_model::~ht_model()
{
this->api->ReleaseMemoryInfo(this->palm_detection_meminfo);
this->api->ReleaseSession(this->palm_detection_session);
this->api->ReleaseValue(this->palm_detection_tensor);
this->api->ReleaseMemoryInfo(this->hand_landmark_meminfo);
this->api->ReleaseSession(this->hand_landmark_session);
this->api->ReleaseValue(this->hand_landmark_tensor);
this->api->ReleaseEnv(this->env);
}
std::vector<Palm7KP>
ht_model::palm_detection(ht_view *htv, const cv::Mat &input)
{
// TODO use opencv to handle input preprocessing
constexpr int hd_size = 128;
constexpr size_t nb_planes = 3;
constexpr size_t size = hd_size * hd_size * nb_planes;
cv::Mat img;
cv::Matx23f back_from_blackbar = blackbar(input, img, {hd_size, hd_size});
float scale_factor = back_from_blackbar(0, 0); // 960/128
assert(img.isContinuous());
constexpr float mean = 128.0f;
constexpr float std = 128.0f;
if (htv->htd->startup_config.palm_detection_use_mediapipe) {
std::vector<uint8_t> combined_planes(size);
planarize(img, combined_planes.data());
for (size_t i = 0; i < size; i++) {
float val = (float)combined_planes[i];
this->palm_detection_data[i] = (val - mean) / std;
}
} else {
assert(img.isContinuous());
for (size_t i = 0; i < size; i++) {
int val = img.data[i];
this->palm_detection_data[i] = (val - mean) / std;
}
}
const char *input_names[1];
if (this->device->startup_config.keypoint_estimation_use_mediapipe) {
input_names[0] = "input";
} else {
input_names[0] = "input:0";
}
static const char *const output_names[] = {"classificators", "regressors"};
OrtValue *output_tensor[] = {nullptr, nullptr};
ORT(Run(this->palm_detection_session, nullptr, input_names, &this->palm_detection_tensor, 1, output_names, 2,
output_tensor));
// TODO define types to handle data
float *classificators = nullptr;
float *regressors = nullptr;
// Output is 896 floats
ORT(GetTensorMutableData(output_tensor[0], (void **)&classificators));
// Output is 896 * 18 floats
ORT(GetTensorMutableData(output_tensor[1], (void **)&regressors));
std::vector<NMSPalm> detections;
for (size_t i = 0; i < 896; ++i) {
const float score = 1.0 / (1.0 + exp(-classificators[i]));
// Let a lot of detections in - they'll be slowly rejected later
if (score <= this->device->dynamic_config.nms_threshold.val) {
continue;
}
const struct anchor *anchor = &anchors[i];
// Boundary box.
NMSPalm det;
float anchx = anchor->x * 128;
float anchy = anchor->y * 128;
float shiftx = regressors[i * 18];
float shifty = regressors[i * 18 + 1];
float w = regressors[i * 18 + 2];
float h = regressors[i * 18 + 3];
float cx = shiftx + anchx;
float cy = shifty + anchy;
struct xrt_vec2 *kps = det.keypoints;
kps[0] = {regressors[i * 18 + 4], regressors[i * 18 + 5]};
kps[1] = {regressors[i * 18 + 6], regressors[i * 18 + 7]};
kps[2] = {regressors[i * 18 + 8], regressors[i * 18 + 9]};
kps[3] = {regressors[i * 18 + 10], regressors[i * 18 + 11]};
kps[4] = {regressors[i * 18 + 12], regressors[i * 18 + 13]};
kps[5] = {regressors[i * 18 + 14], regressors[i * 18 + 15]};
kps[6] = {regressors[i * 18 + 16], regressors[i * 18 + 17]};
for (int i = 0; i < 7; i++) {
struct xrt_vec2 *b = &kps[i];
b->x += anchx;
b->y += anchy;
}
det.bbox.w = w;
det.bbox.h = h;
det.bbox.cx = cx;
det.bbox.cy = cy;
det.confidence = score;
detections.push_back(det);
if (htv->htd->debug_scribble && (htv->htd->dynamic_config.scribble_raw_detections)) {
xrt_vec2 center = transformVecBy2x3(xrt_vec2{cx, cy}, back_from_blackbar);
float sz = det.bbox.w * scale_factor;
cv::rectangle(htv->debug_out_to_this,
{(int)(center.x - (sz / 2)), (int)(center.y - (sz / 2)), (int)sz, (int)sz},
hsv2rgb(0.0f, math_map_ranges(det.confidence, 0.0f, 1.0f, 1.5f, -0.1f),
math_map_ranges(det.confidence, 0.0f, 1.0f, 0.2f, 1.4f)),
1);
for (int i = 0; i < 7; i++) {
handDot(htv->debug_out_to_this, transformVecBy2x3(kps[i], back_from_blackbar),
det.confidence * 7, ((float)i) * (360.0f / 7.0f), det.confidence, 1);
}
}
}
this->api->ReleaseValue(output_tensor[0]);
this->api->ReleaseValue(output_tensor[1]);
std::vector<Palm7KP> output;
if (detections.empty()) {
return output;
}
std::vector<NMSPalm> nms_palms = filterBoxesWeightedAvg(detections, htv->htd->dynamic_config.nms_iou.val);
for (const NMSPalm &cooler : nms_palms) {
// Display box
struct xrt_vec2 tl = {cooler.bbox.cx - cooler.bbox.w / 2, cooler.bbox.cy - cooler.bbox.h / 2};
struct xrt_vec2 bob = transformVecBy2x3(tl, back_from_blackbar);
float sz = cooler.bbox.w * scale_factor;
if (htv->htd->debug_scribble && htv->htd->dynamic_config.scribble_nms_detections) {
cv::rectangle(htv->debug_out_to_this, {(int)bob.x, (int)bob.y, (int)sz, (int)sz},
hsv2rgb(180.0f, math_map_ranges(cooler.confidence, 0.0f, 1.0f, 0.8f, -0.1f),
math_map_ranges(cooler.confidence, 0.0f, 1.0f, 0.2f, 1.4f)),
2);
for (int i = 0; i < 7; i++) {
handDot(htv->debug_out_to_this,
transformVecBy2x3(cooler.keypoints[i], back_from_blackbar),
cooler.confidence * 14, ((float)i) * (360.0f / 7.0f), cooler.confidence, 3);
}
}
Palm7KP this_element;
for (int i = 0; i < 7; i++) {
struct xrt_vec2 b = cooler.keypoints[i];
this_element.kps[i] = transformVecBy2x3(b, back_from_blackbar);
}
this_element.confidence = cooler.confidence;
output.push_back(this_element);
}
return output;
}
Hand2D
ht_model::hand_landmark(const cv::Mat input)
{
std::scoped_lock lock(this->hand_landmark_lock);
// TODO use opencv to handle input preprocessing
constexpr size_t lix = 224;
constexpr size_t liy = 224;
constexpr size_t nb_planes = 3;
cv::Mat planes[nb_planes];
constexpr size_t size = lix * liy * nb_planes;
std::vector<uint8_t> combined_planes(size);
planarize(input, combined_planes.data());
// Normalize - supposedly, the keypoint estimator wants keypoints in [0,1]
for (size_t i = 0; i < size; i++) {
this->hand_landmark_data[i] = (float)combined_planes[i] / 255.0;
}
static const char *const input_names[] = {"input_1"};
static const char *const output_names[] = {"Identity", "Identity_1", "Identity_2"};
OrtValue *output_tensor[] = {nullptr, nullptr, nullptr};
ORT(Run(this->hand_landmark_session, nullptr, input_names, &this->hand_landmark_tensor, 1, output_names, 3,
output_tensor));
Hand2D hand{};
float *landmarks = nullptr;
// Should give a pointer to data that is freed on g_ort->ReleaseValue(output_tensor[0]);.
ORT(GetTensorMutableData(output_tensor[0], (void **)&landmarks));
constexpr int stride = 3;
for (size_t i = 0; i < 21; i++) {
int rt = i * stride;
float x = landmarks[rt];
float y = landmarks[rt + 1];
float z = landmarks[rt + 2];
hand.kps[i].x = x;
hand.kps[i].y = y;
hand.kps[i].z = z;
}
this->api->ReleaseValue(output_tensor[0]);
this->api->ReleaseValue(output_tensor[1]);
this->api->ReleaseValue(output_tensor[2]);
return hand;
}
} // namespace xrt::tracking::hand::old_rgb

View file

@ -1,114 +0,0 @@
// Copyright 2021-2022, Collabora, Ltd.
// SPDX-License-Identifier: BSL-1.0
/*!
* @file
* @brief Code to deal with bounding boxes for camera-based hand-tracking.
* @author Moses Turner <moses@collabora.com>
* @author Marcus Edel <marcus.edel@collabora.com>
* @ingroup drv_ht
*/
#include "rgb_sync.hpp"
#include <math.h>
#include "util/u_box_iou.hpp"
using namespace xrt::auxiliary::util::box_iou;
struct NMSPalm
{
Box bbox;
struct xrt_vec2 keypoints[7];
float confidence;
};
static NMSPalm
weightedAvgBoxes(const std::vector<NMSPalm> &detections)
{
float weight = 0.0f; // or, sum_confidences.
float cx = 0.0f;
float cy = 0.0f;
float size = 0.0f;
NMSPalm out = {};
for (const NMSPalm &detection : detections) {
weight += detection.confidence;
cx += detection.bbox.cx * detection.confidence;
cy += detection.bbox.cy * detection.confidence;
size += detection.bbox.w * .5 * detection.confidence;
size += detection.bbox.h * .5 * detection.confidence;
for (int i = 0; i < 7; i++) {
out.keypoints[i].x += detection.keypoints[i].x * detection.confidence;
out.keypoints[i].y += detection.keypoints[i].y * detection.confidence;
}
}
cx /= weight;
cy /= weight;
size /= weight;
for (int i = 0; i < 7; i++) {
out.keypoints[i].x /= weight;
out.keypoints[i].y /= weight;
}
float bare_confidence = weight / detections.size();
// desmos \frac{1}{1+e^{-.5x}}-.5
float steep = 0.2;
float cent = 0.5;
float exp = detections.size();
float sigmoid_addendum = (1.0f / (1.0f + pow(M_E, (-steep * exp)))) - cent;
float diff_bare_to_one = 1.0f - bare_confidence;
out.confidence = bare_confidence + (sigmoid_addendum * diff_bare_to_one);
// U_LOG_E("Bare %f num %f sig %f diff %f out %f", bare_confidence, exp, sigmoid_addendum, diff_bare_to_one,
// out.confidence);
out.bbox.cx = cx;
out.bbox.cy = cy;
out.bbox.w = size;
out.bbox.h = size;
return out;
}
std::vector<NMSPalm>
filterBoxesWeightedAvg(const std::vector<NMSPalm> &detections, float min_iou)
{
std::vector<std::vector<NMSPalm>> overlaps;
std::vector<NMSPalm> outs;
// U_LOG_D("\n\nStarting filtering boxes. There are %zu boxes to look at.\n", detections.size());
for (const NMSPalm &detection : detections) {
// U_LOG_D("Starting looking at one detection\n");
bool foundAHome = false;
for (size_t i = 0; i < outs.size(); i++) {
float iou = boxIOU(outs[i].bbox, detection.bbox);
// U_LOG_D("IOU is %f\n", iou);
// U_LOG_D("Outs box is %f %f %f %f", outs[i].bbox.cx, outs[i].bbox.cy, outs[i].bbox.w,
// outs[i].bbox.h)
if (iou > min_iou) {
// This one intersects with the whole thing
overlaps[i].push_back(detection);
outs[i] = weightedAvgBoxes(overlaps[i]);
foundAHome = true;
break;
}
}
if (!foundAHome) {
// U_LOG_D("No home\n");
overlaps.push_back({detection});
outs.push_back({detection});
} else {
// U_LOG_D("Found a home!\n");
}
}
// U_LOG_D("Sizeeeeeeeeeeeeeeeeeeeee is %zu\n", outs.size());
return outs;
}

File diff suppressed because it is too large Load diff

View file

@ -1,305 +0,0 @@
// Copyright 2022, Collabora, Ltd.
// SPDX-License-Identifier: BSL-1.0
/*!
* @file
* @brief Old RGB hand tracking header.
* @author Jakob Bornecrantz <jakob@collabora.com>
* @author Moses Turner <moses@collabora.com>
* @ingroup tracking
*/
#pragma once
#include "tracking/t_hand_tracking.h"
#include "os/os_threading.h"
#include "xrt/xrt_device.h"
#include "xrt/xrt_prober.h"
#include "xrt/xrt_frame.h"
#include "xrt/xrt_frameserver.h"
#include "math/m_api.h"
#include "math/m_vec3.h"
#include "math/m_filter_one_euro.h"
#include "util/u_var.h"
#include "util/u_json.h"
#include "util/u_sink.h"
#include "util/u_debug.h"
#include "util/u_device.h"
#include "util/u_template_historybuf.hpp"
#include <opencv2/opencv.hpp>
#include <vector>
namespace xrt::tracking::hand::old_rgb {
using namespace xrt::auxiliary::util;
#define HT_TRACE(htd, ...) U_LOG_IFL_T(htd->log_level, __VA_ARGS__)
#define HT_DEBUG(htd, ...) U_LOG_IFL_D(htd->log_level, __VA_ARGS__)
#define HT_INFO(htd, ...) U_LOG_IFL_I(htd->log_level, __VA_ARGS__)
#define HT_WARN(htd, ...) U_LOG_IFL_W(htd->log_level, __VA_ARGS__)
#define HT_ERROR(htd, ...) U_LOG_IFL_E(htd->log_level, __VA_ARGS__)
#undef EXPERIMENTAL_DATASET_RECORDING
#define FCMIN_BBOX_ORIENTATION 3.0f
#define FCMIN_D_BB0X_ORIENTATION 10.0f
#define BETA_BB0X_ORIENTATION 0.0f
#define FCMIN_BBOX_POSITION 30.0f
#define FCMIN_D_BB0X_POSITION 25.0f
#define BETA_BB0X_POSITION 0.01f
#define FCMIN_HAND 4.0f
#define FCMIN_D_HAND 12.0f
#define BETA_HAND 0.0083f
class ht_model;
enum HandJoint7Keypoint
{
WRIST_7KP = 0,
INDEX_7KP = 1,
MIDDLE_7KP = 2,
RING_7KP = 3,
LITTLE_7KP = 4,
THUMB_METACARPAL_7KP = 5,
THMB_PROXIMAL_7KP = 6
};
enum HandJoint21Keypoint
{
WRIST = 0,
THMB_MCP = 1,
THMB_PXM = 2,
THMB_DST = 3,
THMB_TIP = 4,
INDX_PXM = 5,
INDX_INT = 6,
INDX_DST = 7,
INDX_TIP = 8,
MIDL_PXM = 9,
MIDL_INT = 10,
MIDL_DST = 11,
MIDL_TIP = 12,
RING_PXM = 13,
RING_INT = 14,
RING_DST = 15,
RING_TIP = 16,
LITL_PXM = 17,
LITL_INT = 18,
LITL_DST = 19,
LITL_TIP = 20
};
struct Palm7KP
{
struct xrt_vec2 kps[7];
float confidence; // between 0 and 1
};
struct DetectionModelOutput
{
float rotation;
float size;
xrt_vec2 center;
Palm7KP palm;
cv::Matx23f warp_there;
cv::Matx23f warp_back;
};
// To keep you on your toes. *Don't* think the 2D hand is the same as the 3D!
struct Hand2D
{
struct xrt_vec3 kps[21];
// Third value is depth from ML model. Do not believe the depth.
};
struct Hand3D
{
struct xrt_vec3 kps[21];
float y_disparity_error;
float flow_error;
int idx_l;
int idx_r;
bool rejected_by_smush; // init to false.
float handedness;
uint64_t timestamp;
};
struct HandHistory3D
{
// Index 0 is current frame, index 1 is last frame, index 2 is second to last frame.
// No particular reason to keep the last 5 frames. we only really only use the current and last one.
float handedness;
bool have_prev_hand = false;
double prev_dy;
uint64_t prev_ts_for_alpha; // also in last_hands_unfiltered.back() but go away.
uint64_t first_ts;
uint64_t prev_filtered_ts;
HistoryBuffer<Hand3D, 10> last_hands_unfiltered;
HistoryBuffer<Hand3D, 10> last_hands_filtered;
// Euro filter for 21kps.
m_filter_euro_vec3 filters[21];
int uuid;
};
struct HandHistory2DBBox
{
m_filter_euro_vec2 m_filter_center;
m_filter_euro_vec2 m_filter_direction;
HistoryBuffer<xrt_vec2, 50> wrist_unfiltered;
HistoryBuffer<xrt_vec2, 50> index_unfiltered;
HistoryBuffer<xrt_vec2, 50> middle_unfiltered;
HistoryBuffer<xrt_vec2, 50> pinky_unfiltered;
bool htAlgorithm_approves = false;
};
// Forward declaration for ht_view
struct HandTracking;
struct ht_view
{
HandTracking *htd;
ht_model *htm;
int view;
cv::Matx<double, 4, 1> distortion;
cv::Matx<double, 3, 3> cameraMatrix;
cv::Matx33d rotate_camera_to_stereo_camera; // R1 or R2
cv::Mat run_model_on_this;
cv::Mat debug_out_to_this;
std::vector<HandHistory2DBBox> bbox_histories;
};
struct ht_dynamic_config
{
char name[64];
struct u_var_draggable_f32 hand_fc_min;
struct u_var_draggable_f32 hand_fc_min_d;
struct u_var_draggable_f32 hand_beta;
struct u_var_draggable_f32 max_vel;
struct u_var_draggable_f32 max_acc;
struct u_var_draggable_f32 nms_iou;
struct u_var_draggable_f32 nms_threshold;
struct u_var_draggable_f32 new_detection_threshold;
bool scribble_raw_detections;
bool scribble_nms_detections;
bool scribble_2d_keypoints;
bool scribble_bounding_box;
};
struct ht_startup_config
{
bool palm_detection_use_mediapipe = false;
bool keypoint_estimation_use_mediapipe = false;
enum xrt_format desired_format;
char model_slug[1024];
};
/*!
* Main class of old style RGB hand tracking.
*
* @ingroup aux_tracking
*/
struct HandTracking
{
public:
// Base thing, has to be first.
t_hand_tracking_sync base = {};
struct u_sink_debug debug_sink = {};
struct xrt_size one_view_size_px = {};
#if defined(EXPERIMENTAL_DATASET_RECORDING)
struct
{
struct u_var_button start_json_record = {};
} gui = {};
struct
{
struct gstreamer_pipeline *gp = nullptr;
struct gstreamer_sink *gs = nullptr;
struct xrt_frame_sink *sink = nullptr;
struct xrt_frame_context xfctx = {};
uint64_t offset_ns = {};
uint64_t last_frame_ns = {};
uint64_t current_index = {};
cJSON *output_root = nullptr;
cJSON *output_array = nullptr;
} gst = {};
#endif
struct ht_view views[2] = {};
float baseline = {};
struct xrt_quat stereo_camera_to_left_camera = {};
uint64_t current_frame_timestamp = {};
std::vector<HandHistory3D> histories_3d = {};
struct os_mutex openxr_hand_data_mediator = {};
struct xrt_hand_joint_set hands_for_openxr[2] = {};
uint64_t hands_for_openxr_timestamp = {};
// Only change these when you have unlocked_between_frames, ie. when the hand tracker is between frames.
bool tracking_should_die = {};
bool tracking_should_record_dataset = {};
struct os_mutex unlocked_between_frames = {};
// Change this whenever you want
volatile bool debug_scribble = true;
struct ht_startup_config startup_config = {};
struct ht_dynamic_config dynamic_config = {};
enum u_logging_level log_level = U_LOGGING_INFO;
public:
explicit HandTracking();
~HandTracking();
static inline HandTracking &
fromC(t_hand_tracking_sync *ht_sync)
{
return *reinterpret_cast<HandTracking *>(ht_sync);
}
static void
cCallbackProcess(struct t_hand_tracking_sync *ht_sync,
struct xrt_frame *left_frame,
struct xrt_frame *right_frame,
struct xrt_hand_joint_set *out_left_hand,
struct xrt_hand_joint_set *out_right_hand,
uint64_t *out_timestamp_ns);
static void
cCallbackDestroy(t_hand_tracking_sync *ht_sync);
};
} // namespace xrt::tracking::hand::old_rgb

View file

@ -1,91 +0,0 @@
// Copyright 2021, Collabora, Ltd.
// SPDX-License-Identifier: BSL-1.0
/*!
* @file
* @brief Camera based hand tracking sorting implementation.
* @author Moses Turner <moses@collabora.com>
* @ingroup drv_ht
*/
#pragma once
#include <math.h>
#include <vector>
#include <algorithm>
#include <iostream>
// Other thing: sort by speed? like, if our thing must have suddenly changed directions, add to error?
// Easy enough to do using more complicated structs.
// Like a past thing with position, velocity and timestamp - present thing with position and timestamp.
// typedef bool booool;
struct psort_atom_t
{
size_t idx_1;
size_t idx_2;
float err;
};
bool
comp_err(psort_atom_t one, psort_atom_t two)
{
return (one.err < two.err);
}
template <typename Tp_1, typename Tp_2>
void
naive_sort_permutation_by_error(
// Inputs - shall be initialized with real data before calling. This function shall not modify them in any way.
std::vector<Tp_1> &in_1,
std::vector<Tp_2> &in_2,
// Outputs - shall be uninitialized. This function shall initialize them to the right size and fill them with the
// proper values.
std::vector<bool> &used_1,
std::vector<bool> &used_2,
std::vector<size_t> &out_indices_1,
std::vector<size_t> &out_indices_2,
std::vector<float> &out_errs,
float (*calc_error)(const Tp_1 &one, const Tp_2 &two),
float max_err = std::numeric_limits<float>::max())
{
used_1 = std::vector<bool>(in_1.size()); // silly? Unsure.
used_2 = std::vector<bool>(in_2.size());
size_t out_size = std::min(in_1.size(), in_2.size());
out_indices_1.reserve(out_size);
out_indices_2.reserve(out_size);
std::vector<psort_atom_t> associations;
for (size_t idx_1 = 0; idx_1 < in_1.size(); idx_1++) {
for (size_t idx_2 = 0; idx_2 < in_2.size(); idx_2++) {
float err = calc_error(in_1[idx_1], in_2[idx_2]);
if (err > 0.0f) {
// Negative error means the error calculator thought there was something so bad with
// these that they shouldn't be considered at all.
associations.push_back({idx_1, idx_2, err});
}
}
}
std::sort(associations.begin(), associations.end(), comp_err);
for (size_t i = 0; i < associations.size(); i++) {
psort_atom_t chonk = associations[i];
if (used_1[chonk.idx_1] || used_2[chonk.idx_2] || (chonk.err > max_err)) {
continue;
}
used_1[chonk.idx_1] = true;
used_2[chonk.idx_2] = true;
out_indices_1.push_back(chonk.idx_1);
out_indices_2.push_back(chonk.idx_2);
out_errs.push_back(chonk.err);
}
}