Compare commits

..

3 Commits

12 changed files with 860 additions and 248 deletions
+2
View File
@@ -17,6 +17,7 @@ find_package(nanobind CONFIG REQUIRED)
set(RPT_PYTHON_PACKAGE_DIR "${CMAKE_CURRENT_BINARY_DIR}/rpt")
file(MAKE_DIRECTORY "${RPT_PYTHON_PACKAGE_DIR}")
configure_file("${PROJECT_SOURCE_DIR}/src/rpt/__init__.py" "${RPT_PYTHON_PACKAGE_DIR}/__init__.py" COPYONLY)
configure_file("${PROJECT_SOURCE_DIR}/src/rpt/__init__.pyi" "${RPT_PYTHON_PACKAGE_DIR}/__init__.pyi" COPYONLY)
configure_file("${PROJECT_SOURCE_DIR}/src/rpt/_helpers.py" "${RPT_PYTHON_PACKAGE_DIR}/_helpers.py" COPYONLY)
configure_file("${PROJECT_SOURCE_DIR}/src/rpt/py.typed" "${RPT_PYTHON_PACKAGE_DIR}/py.typed" COPYONLY)
@@ -40,4 +41,5 @@ nanobind_add_stub(rpt_core_stub
)
install(TARGETS rpt_core_ext LIBRARY DESTINATION rpt)
install(FILES "${RPT_PYTHON_PACKAGE_DIR}/__init__.pyi" DESTINATION rpt)
install(FILES "${RPT_PYTHON_PACKAGE_DIR}/_core.pyi" DESTINATION rpt)
+137 -22
View File
@@ -20,6 +20,7 @@ namespace
using PoseArray2D =
nb::ndarray<nb::numpy, const float, nb::shape<-1, -1, -1, 3>, nb::c_contig>;
using CountArray = nb::ndarray<nb::numpy, const uint32_t, nb::shape<-1>, nb::c_contig>;
using TrackIdArray = nb::ndarray<nb::numpy, const int64_t, nb::shape<-1>, nb::c_contig>;
using PoseArray3DConst =
nb::ndarray<nb::numpy, const float, nb::shape<-1, -1, 4>, nb::c_contig>;
using PoseArray3D = nb::ndarray<nb::numpy, float, nb::shape<-1, -1, 4>, nb::c_contig>;
@@ -58,6 +59,24 @@ PoseBatch3DView pose_batch3d_view_from_numpy(const PoseArray3DConst &poses_3d)
};
}
TrackedPoseBatch3DView tracked_pose_batch_view_from_numpy(
const PoseArray3DConst &poses_3d,
const TrackIdArray &track_ids)
{
if (poses_3d.shape(0) != track_ids.shape(0))
{
throw std::invalid_argument(
"previous_poses_3d and previous_track_ids must have the same number of tracks.");
}
return TrackedPoseBatch3DView {
track_ids.data(),
poses_3d.data(),
static_cast<size_t>(poses_3d.shape(0)),
static_cast<size_t>(poses_3d.shape(1)),
};
}
PoseArray3D pose_batch_to_numpy(PoseBatch3D batch)
{
auto *storage = new std::vector<float>(std::move(batch.data));
@@ -139,15 +158,54 @@ NB_MODULE(_core, m)
.value("FISHEYE", CameraModel::Fisheye);
nb::class_<Camera>(m, "Camera")
.def(nb::init<>())
.def_rw("name", &Camera::name)
.def_rw("K", &Camera::K)
.def_rw("DC", &Camera::DC)
.def_rw("R", &Camera::R)
.def_rw("T", &Camera::T)
.def_rw("width", &Camera::width)
.def_rw("height", &Camera::height)
.def_rw("model", &Camera::model)
.def_prop_ro("name", [](const Camera &camera)
{
return camera.name;
})
.def_prop_ro("K", [](const Camera &camera)
{
return camera.K;
})
.def_prop_ro("DC", [](const Camera &camera)
{
return camera.DC;
})
.def_prop_ro("R", [](const Camera &camera)
{
return camera.R;
})
.def_prop_ro("T", [](const Camera &camera)
{
return camera.T;
})
.def_prop_ro("width", [](const Camera &camera)
{
return camera.width;
})
.def_prop_ro("height", [](const Camera &camera)
{
return camera.height;
})
.def_prop_ro("model", [](const Camera &camera)
{
return camera.model;
})
.def_prop_ro("invR", [](const Camera &camera)
{
return camera.invR;
})
.def_prop_ro("center", [](const Camera &camera)
{
return camera.center;
})
.def_prop_ro("newK", [](const Camera &camera)
{
return camera.newK;
})
.def_prop_ro("invK", [](const Camera &camera)
{
return camera.invK;
})
.def("__repr__", [](const Camera &camera)
{
return camera.to_string();
@@ -177,6 +235,7 @@ NB_MODULE(_core, m)
nb::class_<PreviousPoseMatch>(m, "PreviousPoseMatch")
.def(nb::init<>())
.def_rw("previous_pose_index", &PreviousPoseMatch::previous_pose_index)
.def_rw("previous_track_id", &PreviousPoseMatch::previous_track_id)
.def_rw("score_view1", &PreviousPoseMatch::score_view1)
.def_rw("score_view2", &PreviousPoseMatch::score_view2)
.def_rw("matched_view1", &PreviousPoseMatch::matched_view1)
@@ -235,6 +294,34 @@ NB_MODULE(_core, m)
return merged_poses_to_numpy_copy(merge.merged_poses);
}, nb::rv_policy::move);
nb::enum_<AssociationStatus>(m, "AssociationStatus")
.value("MATCHED", AssociationStatus::Matched)
.value("NEW", AssociationStatus::New)
.value("AMBIGUOUS", AssociationStatus::Ambiguous);
nb::class_<AssociationReport>(m, "AssociationReport")
.def(nb::init<>())
.def_rw("pose_previous_indices", &AssociationReport::pose_previous_indices)
.def_rw("pose_previous_track_ids", &AssociationReport::pose_previous_track_ids)
.def_rw("pose_status", &AssociationReport::pose_status)
.def_rw("pose_candidate_previous_indices", &AssociationReport::pose_candidate_previous_indices)
.def_rw("pose_candidate_previous_track_ids", &AssociationReport::pose_candidate_previous_track_ids)
.def_rw("unmatched_previous_indices", &AssociationReport::unmatched_previous_indices)
.def_rw("unmatched_previous_track_ids", &AssociationReport::unmatched_previous_track_ids)
.def_rw("new_pose_indices", &AssociationReport::new_pose_indices)
.def_rw("ambiguous_pose_indices", &AssociationReport::ambiguous_pose_indices);
nb::class_<FinalPoseAssociationDebug>(m, "FinalPoseAssociationDebug")
.def(nb::init<>())
.def_rw("final_pose_index", &FinalPoseAssociationDebug::final_pose_index)
.def_rw("source_core_proposal_indices", &FinalPoseAssociationDebug::source_core_proposal_indices)
.def_rw("source_pair_indices", &FinalPoseAssociationDebug::source_pair_indices)
.def_rw("candidate_previous_indices", &FinalPoseAssociationDebug::candidate_previous_indices)
.def_rw("candidate_previous_track_ids", &FinalPoseAssociationDebug::candidate_previous_track_ids)
.def_rw("resolved_previous_index", &FinalPoseAssociationDebug::resolved_previous_index)
.def_rw("resolved_previous_track_id", &FinalPoseAssociationDebug::resolved_previous_track_id)
.def_rw("status", &FinalPoseAssociationDebug::status);
nb::class_<TriangulationTrace>(m, "TriangulationTrace")
.def(nb::init<>())
.def_rw("pairs", &TriangulationTrace::pairs)
@@ -243,11 +330,33 @@ NB_MODULE(_core, m)
.def_rw("grouping", &TriangulationTrace::grouping)
.def_rw("full_proposals", &TriangulationTrace::full_proposals)
.def_rw("merge", &TriangulationTrace::merge)
.def_rw("association", &TriangulationTrace::association)
.def_rw("final_pose_associations", &TriangulationTrace::final_pose_associations)
.def_prop_ro("final_poses", [](const TriangulationTrace &trace)
{
return pose_batch_to_numpy_copy(trace.final_poses);
}, nb::rv_policy::move);
nb::class_<TriangulationResult>(m, "TriangulationResult")
.def(nb::init<>())
.def_rw("association", &TriangulationResult::association)
.def_prop_ro("poses_3d", [](const TriangulationResult &result)
{
return pose_batch_to_numpy_copy(result.poses);
}, nb::rv_policy::move);
m.def(
"make_camera",
&make_camera,
"name"_a,
"K"_a,
"DC"_a,
"R"_a,
"T"_a,
"width"_a,
"height"_a,
"model"_a);
m.def(
"build_pair_candidates",
[](const PoseArray2D &poses_2d, const CountArray &person_counts)
@@ -262,17 +371,19 @@ NB_MODULE(_core, m)
[](const PoseArray2D &poses_2d,
const CountArray &person_counts,
const TriangulationConfig &config,
const PoseArray3DConst &previous_poses_3d)
const PoseArray3DConst &previous_poses_3d,
const TrackIdArray &previous_track_ids)
{
return filter_pairs_with_previous_poses(
pose_batch_view_from_numpy(poses_2d, person_counts),
config,
pose_batch3d_view_from_numpy(previous_poses_3d));
tracked_pose_batch_view_from_numpy(previous_poses_3d, previous_track_ids));
},
"poses_2d"_a,
"person_counts"_a,
"config"_a,
"previous_poses_3d"_a);
"previous_poses_3d"_a,
"previous_track_ids"_a);
m.def(
"triangulate_debug",
@@ -291,9 +402,11 @@ NB_MODULE(_core, m)
[](const PoseArray2D &poses_2d,
const CountArray &person_counts,
const TriangulationConfig &config,
const PoseArray3DConst &previous_poses_3d)
const PoseArray3DConst &previous_poses_3d,
const TrackIdArray &previous_track_ids)
{
const PoseBatch3DView previous_view = pose_batch3d_view_from_numpy(previous_poses_3d);
const TrackedPoseBatch3DView previous_view =
tracked_pose_batch_view_from_numpy(previous_poses_3d, previous_track_ids);
return triangulate_debug(
pose_batch_view_from_numpy(poses_2d, person_counts),
config,
@@ -302,7 +415,8 @@ NB_MODULE(_core, m)
"poses_2d"_a,
"person_counts"_a,
"config"_a,
"previous_poses_3d"_a);
"previous_poses_3d"_a,
"previous_track_ids"_a);
m.def(
"triangulate_poses",
@@ -319,21 +433,22 @@ NB_MODULE(_core, m)
"config"_a);
m.def(
"triangulate_poses",
"triangulate_with_report",
[](const PoseArray2D &poses_2d,
const CountArray &person_counts,
const TriangulationConfig &config,
const PoseArray3DConst &previous_poses_3d)
const PoseArray3DConst &previous_poses_3d,
const TrackIdArray &previous_track_ids)
{
const PoseBatch3DView previous_view = pose_batch3d_view_from_numpy(previous_poses_3d);
const PoseBatch3D poses_3d = triangulate_poses(
const TriangulationResult result = triangulate_with_report(
pose_batch_view_from_numpy(poses_2d, person_counts),
config,
&previous_view);
return pose_batch_to_numpy(poses_3d);
tracked_pose_batch_view_from_numpy(previous_poses_3d, previous_track_ids));
return result;
},
"poses_2d"_a,
"person_counts"_a,
"config"_a,
"previous_poses_3d"_a);
"previous_poses_3d"_a,
"previous_track_ids"_a);
}
-19
View File
@@ -1,19 +0,0 @@
#pragma once
#include <array>
#include "camera.hpp"
struct CachedCamera
{
const Camera cam;
const std::array<std::array<float, 3>, 3> invR;
const std::array<float, 3> center;
const std::array<std::array<float, 3>, 3> newK;
const std::array<std::array<float, 3>, 3> invK;
};
CachedCamera cache_camera(const Camera &camera);
void undistort_point_pinhole(std::array<float, 3> &point, const std::array<float, 5> &distortion);
void undistort_point_fisheye(std::array<float, 3> &point, const std::array<float, 5> &distortion);
+29 -11
View File
@@ -1,12 +1,12 @@
#include <array>
#include <cmath>
#include <iomanip>
#include <stdexcept>
#include <sstream>
#include <stdexcept>
#include <utility>
#include <vector>
#include <cmath>
#include "cached_camera.hpp"
#include "camera.hpp"
namespace
{
@@ -156,28 +156,46 @@ std::ostream &operator<<(std::ostream &out, const Camera &cam)
// =================================================================================================
// =================================================================================================
CachedCamera cache_camera(const Camera &cam)
Camera make_camera(
std::string name,
std::array<std::array<float, 3>, 3> K,
std::array<float, 5> DC,
std::array<std::array<float, 3>, 3> R,
std::array<std::array<float, 1>, 3> T,
int width,
int height,
CameraModel model)
{
const std::array<std::array<float, 3>, 3> invR = transpose3x3(cam.R);
Camera cam {
.name = std::move(name),
.K = K,
.DC = DC,
.R = R,
.T = T,
.width = width,
.height = height,
.model = model,
};
cam.invR = transpose3x3(cam.R);
// Camera center:
// C = -(Rᵀ * t) = -(Rᵀ * (R * (T * -1))) = -(Rᵀ * (R * -T)) = -(Rᵀ * -R * T) = -(-T) = T
const std::array<float, 3> center = {cam.T[0][0], cam.T[1][0], cam.T[2][0]};
cam.center = {cam.T[0][0], cam.T[1][0], cam.T[2][0]};
// Undistort camera matrix
// As with the undistortion, the own implementation avoids some overhead compared to OpenCV
std::array<std::array<float, 3>, 3> newK;
if (cam.model == CameraModel::Fisheye)
{
newK = calc_optimal_camera_matrix_fisheye(cam, 1.0f, {cam.width, cam.height});
cam.newK = calc_optimal_camera_matrix_fisheye(cam, 1.0f, {cam.width, cam.height});
}
else
{
newK = calc_optimal_camera_matrix_pinhole(cam, 1.0f, {cam.width, cam.height});
cam.newK = calc_optimal_camera_matrix_pinhole(cam, 1.0f, {cam.width, cam.height});
}
const std::array<std::array<float, 3>, 3> invK = invert3x3(newK);
cam.invK = invert3x3(cam.newK);
return CachedCamera {cam, invR, center, newK, invK};
return cam;
}
// =================================================================================================
+19 -2
View File
@@ -25,10 +25,27 @@ struct Camera
std::array<float, 5> DC = {0.0f, 0.0f, 0.0f, 0.0f, 0.0f};
std::array<std::array<float, 3>, 3> R;
std::array<std::array<float, 1>, 3> T;
int width;
int height;
int width = 0;
int height = 0;
CameraModel model = CameraModel::Pinhole;
std::array<std::array<float, 3>, 3> invR {};
std::array<float, 3> center {};
std::array<std::array<float, 3>, 3> newK {};
std::array<std::array<float, 3>, 3> invK {};
friend std::ostream &operator<<(std::ostream &out, Camera const &camera);
std::string to_string() const;
};
Camera make_camera(
std::string name,
std::array<std::array<float, 3>, 3> K,
std::array<float, 5> DC,
std::array<std::array<float, 3>, 3> R,
std::array<std::array<float, 1>, 3> T,
int width,
int height,
CameraModel model);
void undistort_point_pinhole(std::array<float, 3> &point, const std::array<float, 5> &distortion);
void undistort_point_fisheye(std::array<float, 3> &point, const std::array<float, 5> &distortion);
+10
View File
@@ -43,6 +43,16 @@ const float &PoseBatch3DView::at(size_t person, size_t joint, size_t coord) cons
return data[pose3d_offset(person, joint, coord, num_joints)];
}
int64_t TrackedPoseBatch3DView::track_id(size_t person) const
{
return track_ids[person];
}
const float &TrackedPoseBatch3DView::at(size_t person, size_t joint, size_t coord) const
{
return data[pose3d_offset(person, joint, coord, num_joints)];
}
const float &PoseBatch2D::at(size_t view, size_t person, size_t joint, size_t coord) const
{
return data[pose2d_offset(view, person, joint, coord, max_persons, num_joints)];
+78 -37
View File
@@ -34,6 +34,17 @@ struct PoseBatch3DView
const float &at(size_t person, size_t joint, size_t coord) const;
};
struct TrackedPoseBatch3DView
{
const int64_t *track_ids = nullptr;
const float *data = nullptr;
size_t num_persons = 0;
size_t num_joints = 0;
int64_t track_id(size_t person) const;
const float &at(size_t person, size_t joint, size_t coord) const;
};
struct PoseBatch2D
{
std::vector<float> data;
@@ -78,6 +89,7 @@ struct PairCandidate
struct PreviousPoseMatch
{
int previous_pose_index = -1;
int64_t previous_track_id = -1;
float score_view1 = 0.0f;
float score_view2 = 0.0f;
bool matched_view1 = false;
@@ -131,6 +143,38 @@ struct MergeDebug
std::vector<std::vector<int>> group_proposal_indices;
};
enum class AssociationStatus
{
Matched,
New,
Ambiguous,
};
struct AssociationReport
{
std::vector<int> pose_previous_indices;
std::vector<int64_t> pose_previous_track_ids;
std::vector<AssociationStatus> pose_status;
std::vector<std::vector<int>> pose_candidate_previous_indices;
std::vector<std::vector<int64_t>> pose_candidate_previous_track_ids;
std::vector<int> unmatched_previous_indices;
std::vector<int64_t> unmatched_previous_track_ids;
std::vector<int> new_pose_indices;
std::vector<int> ambiguous_pose_indices;
};
struct FinalPoseAssociationDebug
{
int final_pose_index = -1;
std::vector<int> source_core_proposal_indices;
std::vector<int> source_pair_indices;
std::vector<int> candidate_previous_indices;
std::vector<int64_t> candidate_previous_track_ids;
int resolved_previous_index = -1;
int64_t resolved_previous_track_id = -1;
AssociationStatus status = AssociationStatus::New;
};
struct TriangulationTrace
{
std::vector<PairCandidate> pairs;
@@ -139,9 +183,17 @@ struct TriangulationTrace
GroupingDebug grouping;
std::vector<FullProposalDebug> full_proposals;
MergeDebug merge;
AssociationReport association;
std::vector<FinalPoseAssociationDebug> final_pose_associations;
PoseBatch3D final_poses;
};
struct TriangulationResult
{
PoseBatch3D poses;
AssociationReport association;
};
// =================================================================================================
struct TriangulationOptions
@@ -165,40 +217,15 @@ std::vector<PairCandidate> build_pair_candidates(const PoseBatch2DView &poses_2d
PreviousPoseFilterDebug filter_pairs_with_previous_poses(
const PoseBatch2DView &poses_2d,
const TriangulationConfig &config,
const PoseBatch3DView &previous_poses_3d,
const TrackedPoseBatch3DView &previous_poses_3d,
const TriangulationOptions *options_override = nullptr);
inline PreviousPoseFilterDebug filter_pairs_with_previous_poses(
const PoseBatch2D &poses_2d,
const TriangulationConfig &config,
const PoseBatch3D &previous_poses_3d,
const TriangulationOptions *options_override = nullptr)
{
return filter_pairs_with_previous_poses(poses_2d.view(), config, previous_poses_3d.view(), options_override);
}
TriangulationTrace triangulate_debug(
const PoseBatch2DView &poses_2d,
const TriangulationConfig &config,
const PoseBatch3DView *previous_poses_3d = nullptr,
const TrackedPoseBatch3DView *previous_poses_3d = nullptr,
const TriangulationOptions *options_override = nullptr);
inline TriangulationTrace triangulate_debug(
const PoseBatch2D &poses_2d,
const TriangulationConfig &config,
const PoseBatch3D *previous_poses_3d = nullptr,
const TriangulationOptions *options_override = nullptr)
{
PoseBatch3DView previous_view_storage;
const PoseBatch3DView *previous_view = nullptr;
if (previous_poses_3d != nullptr)
{
previous_view_storage = previous_poses_3d->view();
previous_view = &previous_view_storage;
}
return triangulate_debug(poses_2d.view(), config, previous_view, options_override);
}
// =================================================================================================
/**
@@ -213,21 +240,35 @@ inline TriangulationTrace triangulate_debug(
PoseBatch3D triangulate_poses(
const PoseBatch2DView &poses_2d,
const TriangulationConfig &config,
const PoseBatch3DView *previous_poses_3d = nullptr,
const TriangulationOptions *options_override = nullptr);
TriangulationResult triangulate_with_report(
const PoseBatch2DView &poses_2d,
const TriangulationConfig &config,
const TrackedPoseBatch3DView &previous_poses_3d,
const TriangulationOptions *options_override = nullptr);
inline PoseBatch3D triangulate_poses(
const PoseBatch2D &poses_2d,
const TriangulationConfig &config,
const PoseBatch3D *previous_poses_3d = nullptr,
const TriangulationOptions *options_override = nullptr)
{
PoseBatch3DView previous_view_storage;
const PoseBatch3DView *previous_view = nullptr;
if (previous_poses_3d != nullptr)
{
previous_view_storage = previous_poses_3d->view();
previous_view = &previous_view_storage;
}
return triangulate_poses(poses_2d.view(), config, previous_view, options_override);
return triangulate_poses(poses_2d.view(), config, options_override);
}
inline TriangulationTrace triangulate_debug(
const PoseBatch2D &poses_2d,
const TriangulationConfig &config,
const TriangulationOptions *options_override = nullptr)
{
return triangulate_debug(poses_2d.view(), config, nullptr, options_override);
}
inline TriangulationResult triangulate_with_report(
const PoseBatch2D &poses_2d,
const TriangulationConfig &config,
const TrackedPoseBatch3DView &previous_poses_3d,
const TriangulationOptions *options_override = nullptr)
{
return triangulate_with_report(poses_2d.view(), config, previous_poses_3d, options_override);
}
+244 -130
View File
@@ -9,9 +9,9 @@
#include <stdexcept>
#include <string_view>
#include <unordered_map>
#include <unordered_set>
#include "interface.hpp"
#include "cached_camera.hpp"
namespace
{
@@ -25,73 +25,14 @@ size_t packed_pose_offset(size_t pose, size_t joint, size_t coord, size_t num_jo
return (((pose * num_joints) + joint) * 3) + coord;
}
[[maybe_unused]] static void print_2d_poses(const Pose2D &poses)
{
std::cout << "Poses: (" << poses.size() << ", 3)[" << std::endl;
for (const auto &pose : poses)
{
std::cout << " [";
for (size_t i = 0; i < 3; ++i)
{
std::cout << std::fixed << std::setprecision(3) << pose[i];
if (i < 2)
{
std::cout << ", ";
}
}
std::cout << "]" << std::endl;
}
std::cout << "]" << std::endl;
}
[[maybe_unused]] static void print_3d_poses(const Pose3D &poses)
{
std::cout << "Poses: (" << poses.size() << ", 4)[" << std::endl;
for (const auto &pose : poses)
{
std::cout << " [";
for (size_t i = 0; i < 4; ++i)
{
std::cout << std::fixed << std::setprecision(3) << pose[i];
if (i < 3)
{
std::cout << ", ";
}
}
std::cout << "]" << std::endl;
}
std::cout << "]" << std::endl;
}
[[maybe_unused]] static void print_allpairs(const std::vector<PosePair> &all_pairs)
{
std::cout << "All pairs: [" << std::endl;
for (const auto &pair : all_pairs)
{
const auto &tuple_part = pair.first;
const auto &pair_part = pair.second;
std::cout << "("
<< std::get<0>(tuple_part) << ", "
<< std::get<1>(tuple_part) << ", "
<< std::get<2>(tuple_part) << ", "
<< std::get<3>(tuple_part) << ")";
std::cout << ", ("
<< pair_part.first << ", "
<< pair_part.second << ")"
<< std::endl;
}
std::cout << "]" << std::endl;
}
std::array<float, 3> undistort_point(
const std::array<float, 3> &raw_point, const CachedCamera &icam)
const std::array<float, 3> &raw_point, const Camera &icam)
{
std::array<float, 3> point = raw_point;
const float ifx_old = 1.0f / icam.cam.K[0][0];
const float ify_old = 1.0f / icam.cam.K[1][1];
const float cx_old = icam.cam.K[0][2];
const float cy_old = icam.cam.K[1][2];
const float ifx_old = 1.0f / icam.K[0][0];
const float ify_old = 1.0f / icam.K[1][1];
const float cx_old = icam.K[0][2];
const float cy_old = icam.K[1][2];
const float fx_new = icam.newK[0][0];
const float fy_new = icam.newK[1][1];
const float cx_new = icam.newK[0][2];
@@ -100,21 +41,21 @@ std::array<float, 3> undistort_point(
point[0] = (point[0] - cx_old) * ifx_old;
point[1] = (point[1] - cy_old) * ify_old;
if (icam.cam.model == CameraModel::Fisheye)
if (icam.model == CameraModel::Fisheye)
{
undistort_point_fisheye(point, icam.cam.DC);
undistort_point_fisheye(point, icam.DC);
}
else
{
undistort_point_pinhole(point, icam.cam.DC);
undistort_point_pinhole(point, icam.DC);
}
point[0] = (point[0] * fx_new) + cx_new;
point[1] = (point[1] * fy_new) + cy_new;
const float mask_offset = (icam.cam.width + icam.cam.height) / 20.0f;
if (point[0] < -mask_offset || point[0] >= icam.cam.width + mask_offset ||
point[1] < -mask_offset || point[1] >= icam.cam.height + mask_offset)
const float mask_offset = (icam.width + icam.height) / 20.0f;
if (point[0] < -mask_offset || point[0] >= icam.width + mask_offset ||
point[1] < -mask_offset || point[1] >= icam.height + mask_offset)
{
point = {0.0f, 0.0f, 0.0f};
}
@@ -127,7 +68,7 @@ class PackedPoseStore2D
public:
PackedPoseStore2D(
const PoseBatch2DView &source,
const std::vector<CachedCamera> &internal_cameras)
const std::vector<Camera> &internal_cameras)
: person_counts(source.num_views),
view_offsets(source.num_views),
num_views(source.num_views),
@@ -225,17 +166,17 @@ private:
struct PreparedInputs
{
std::vector<CachedCamera> internal_cameras;
const std::vector<Camera> *internal_cameras = nullptr;
std::vector<size_t> core_joint_idx;
std::vector<std::array<size_t, 2>> core_limbs_idx;
PackedPoseStore2D packed_poses;
PreparedInputs(
std::vector<CachedCamera> cameras_in,
const std::vector<Camera> &cameras_in,
std::vector<size_t> core_joint_idx_in,
std::vector<std::array<size_t, 2>> core_limbs_idx_in,
PackedPoseStore2D packed_poses_in)
: internal_cameras(std::move(cameras_in)),
: internal_cameras(&cameras_in),
core_joint_idx(std::move(core_joint_idx_in)),
core_limbs_idx(std::move(core_limbs_idx_in)),
packed_poses(std::move(packed_poses_in))
@@ -250,6 +191,15 @@ struct PreviousProjectionCache
std::vector<Pose3D> core_poses;
};
struct FinalAssociationState
{
std::vector<int> candidate_previous_indices;
std::vector<int64_t> candidate_previous_track_ids;
int resolved_previous_index = -1;
int64_t resolved_previous_track_id = -1;
AssociationStatus status = AssociationStatus::New;
};
constexpr std::array<std::string_view, 12> kCoreJoints = {
"shoulder_left",
"shoulder_right",
@@ -278,24 +228,24 @@ constexpr std::array<std::pair<std::string_view, std::string_view>, 8> kCoreLimb
std::vector<PairCandidate> build_pair_candidates_from_packed(const PackedPoseStore2D &packed_poses);
PreviousProjectionCache project_previous_poses(
const PoseBatch3DView &previous_poses_3d,
const std::vector<CachedCamera> &internal_cameras,
const TrackedPoseBatch3DView &previous_poses_3d,
const std::vector<Camera> &internal_cameras,
const std::vector<size_t> &core_joint_idx);
PreviousPoseFilterDebug filter_pairs_with_previous_poses_impl(
const PackedPoseStore2D &packed_poses,
const std::vector<CachedCamera> &internal_cameras,
const std::vector<Camera> &internal_cameras,
const std::vector<size_t> &core_joint_idx,
const std::vector<PairCandidate> &pairs,
const TriangulationOptions &options,
const PoseBatch3DView &previous_poses_3d);
const TrackedPoseBatch3DView &previous_poses_3d);
float calc_pose_score(
const Pose2D &pose,
const Pose2D &reference_pose,
const std::vector<float> &dists,
const CachedCamera &icam);
const Camera &icam);
std::tuple<std::vector<Pose2D>, std::vector<std::vector<float>>> project_poses(
const std::vector<Pose3D> &poses_3d,
const CachedCamera &icam,
const Camera &icam,
bool calc_dists);
std::vector<float> score_projection(
const Pose2D &pose,
@@ -306,8 +256,8 @@ std::vector<float> score_projection(
std::pair<Pose3D, float> triangulate_and_score(
const Pose2D &pose1,
const Pose2D &pose2,
const CachedCamera &cam1,
const CachedCamera &cam2,
const Camera &cam1,
const Camera &cam2,
const std::array<std::array<float, 3>, 2> &roomparams,
const std::vector<std::array<size_t, 2>> &core_limbs_idx);
std::vector<GroupedPose> calc_grouping(
@@ -339,7 +289,7 @@ TriangulationTrace triangulate_debug_impl(
const std::vector<Camera> &cameras,
const std::array<std::array<float, 3>, 2> &roomparams,
const std::vector<std::string> &joint_names,
const PoseBatch3DView *previous_poses_3d,
const TrackedPoseBatch3DView *previous_poses_3d,
const TriangulationOptions &options);
PreparedInputs prepare_inputs(
@@ -379,13 +329,6 @@ PreparedInputs prepare_inputs(
}
}
std::vector<CachedCamera> internal_cameras;
internal_cameras.reserve(cameras.size());
for (const auto &camera : cameras)
{
internal_cameras.push_back(cache_camera(camera));
}
std::vector<size_t> core_joint_idx;
core_joint_idx.reserve(kCoreJoints.size());
for (const auto &joint : kCoreJoints)
@@ -405,14 +348,47 @@ PreparedInputs prepare_inputs(
static_cast<size_t>(std::distance(kCoreJoints.begin(), it2))});
}
PackedPoseStore2D packed_poses(poses_2d, internal_cameras);
PackedPoseStore2D packed_poses(poses_2d, cameras);
return PreparedInputs(
std::move(internal_cameras),
cameras,
std::move(core_joint_idx),
std::move(core_limbs_idx),
std::move(packed_poses));
}
void validate_previous_tracks(
const TrackedPoseBatch3DView &previous_poses_3d,
const std::vector<std::string> &joint_names)
{
if (previous_poses_3d.num_persons == 0)
{
return;
}
if (previous_poses_3d.track_ids == nullptr)
{
throw std::invalid_argument("previous_track_ids must not be null.");
}
if (previous_poses_3d.data == nullptr)
{
throw std::invalid_argument("previous_poses_3d data must not be null.");
}
if (previous_poses_3d.num_joints != joint_names.size())
{
throw std::invalid_argument("previous_poses_3d must use the same joint count as joint_names.");
}
std::unordered_set<int64_t> seen_track_ids;
seen_track_ids.reserve(previous_poses_3d.num_persons);
for (size_t person = 0; person < previous_poses_3d.num_persons; ++person)
{
const int64_t track_id = previous_poses_3d.track_id(person);
if (!seen_track_ids.insert(track_id).second)
{
throw std::invalid_argument("previous_track_ids must be unique.");
}
}
}
std::vector<PairCandidate> build_pair_candidates_from_packed(const PackedPoseStore2D &packed_poses)
{
std::vector<PairCandidate> pairs;
@@ -440,8 +416,8 @@ std::vector<PairCandidate> build_pair_candidates_from_packed(const PackedPoseSto
}
PreviousProjectionCache project_previous_poses(
const PoseBatch3DView &previous_poses_3d,
const std::vector<CachedCamera> &internal_cameras,
const TrackedPoseBatch3DView &previous_poses_3d,
const std::vector<Camera> &internal_cameras,
const std::vector<size_t> &core_joint_idx)
{
PreviousProjectionCache cache;
@@ -476,7 +452,7 @@ float calc_pose_score(
const Pose2D &pose,
const Pose2D &reference_pose,
const std::vector<float> &dists,
const CachedCamera &icam)
const Camera &icam)
{
const float min_score = 0.1f;
std::vector<bool> mask(pose.size(), false);
@@ -494,7 +470,7 @@ float calc_pose_score(
return 0.0f;
}
const float iscale = (icam.cam.width + icam.cam.height) * 0.5f;
const float iscale = (icam.width + icam.height) * 0.5f;
std::vector<float> scores = score_projection(pose, reference_pose, dists, mask, iscale);
const size_t drop_k = static_cast<size_t>(pose.size() * 0.2f);
if (drop_k > 0)
@@ -512,11 +488,11 @@ float calc_pose_score(
PreviousPoseFilterDebug filter_pairs_with_previous_poses_impl(
const PackedPoseStore2D &packed_poses,
const std::vector<CachedCamera> &internal_cameras,
const std::vector<Camera> &internal_cameras,
const std::vector<size_t> &core_joint_idx,
const std::vector<PairCandidate> &pairs,
const TriangulationOptions &options,
const PoseBatch3DView &previous_poses_3d)
const TrackedPoseBatch3DView &previous_poses_3d)
{
PreviousPoseFilterDebug debug;
debug.used_previous_poses = true;
@@ -567,6 +543,7 @@ PreviousPoseFilterDebug filter_pairs_with_previous_poses_impl(
{
best_match = PreviousPoseMatch {
static_cast<int>(previous_index),
previous_poses_3d.track_id(previous_index),
score_view1,
score_view2,
true,
@@ -582,6 +559,7 @@ PreviousPoseFilterDebug filter_pairs_with_previous_poses_impl(
{
best_match = PreviousPoseMatch {
static_cast<int>(previous_index),
previous_poses_3d.track_id(previous_index),
score_view1,
score_view2,
matched_view1,
@@ -616,16 +594,15 @@ TriangulationTrace triangulate_debug_impl(
const std::vector<Camera> &cameras,
const std::array<std::array<float, 3>, 2> &roomparams,
const std::vector<std::string> &joint_names,
const PoseBatch3DView *previous_poses_3d,
const TrackedPoseBatch3DView *previous_poses_3d,
const TriangulationOptions &options)
{
TriangulationTrace trace;
trace.final_poses.num_joints = joint_names.size();
if (previous_poses_3d != nullptr && previous_poses_3d->num_persons > 0 &&
previous_poses_3d->num_joints != joint_names.size())
if (previous_poses_3d != nullptr)
{
throw std::invalid_argument("previous_poses_3d must use the same joint count as joint_names.");
validate_previous_tracks(*previous_poses_3d, joint_names);
}
PreparedInputs prepared = prepare_inputs(poses_2d, cameras, joint_names);
@@ -643,7 +620,7 @@ TriangulationTrace triangulate_debug_impl(
{
trace.previous_filter = filter_pairs_with_previous_poses_impl(
prepared.packed_poses,
prepared.internal_cameras,
*prepared.internal_cameras,
prepared.core_joint_idx,
trace.pairs,
options,
@@ -663,8 +640,8 @@ TriangulationTrace triangulate_debug_impl(
for (size_t i = 0; i < active_pairs.size(); ++i)
{
const PairCandidate &pair = active_pairs[i];
const CachedCamera &cam1 = prepared.internal_cameras[static_cast<size_t>(pair.view1)];
const CachedCamera &cam2 = prepared.internal_cameras[static_cast<size_t>(pair.view2)];
const Camera &cam1 = (*prepared.internal_cameras)[static_cast<size_t>(pair.view1)];
const Camera &cam2 = (*prepared.internal_cameras)[static_cast<size_t>(pair.view2)];
const Pose2D pose1_core = prepared.packed_poses.pose(
static_cast<size_t>(pair.view1), static_cast<size_t>(pair.person1), prepared.core_joint_idx);
const Pose2D pose2_core = prepared.packed_poses.pose(
@@ -849,8 +826,8 @@ TriangulationTrace triangulate_debug_impl(
kept_pose_pairs[i].second.first,
kept_pose_pairs[i].second.second,
};
const CachedCamera &cam1 = prepared.internal_cameras[static_cast<size_t>(pair.view1)];
const CachedCamera &cam2 = prepared.internal_cameras[static_cast<size_t>(pair.view2)];
const Camera &cam1 = (*prepared.internal_cameras)[static_cast<size_t>(pair.view1)];
const Camera &cam2 = (*prepared.internal_cameras)[static_cast<size_t>(pair.view2)];
Pose2D pose1 = prepared.packed_poses.pose(static_cast<size_t>(pair.view1), static_cast<size_t>(pair.person1));
Pose2D pose2 = prepared.packed_poses.pose(static_cast<size_t>(pair.view2), static_cast<size_t>(pair.person2));
@@ -893,11 +870,68 @@ TriangulationTrace triangulate_debug_impl(
poses.push_back(full_pose_buffer[static_cast<size_t>(index)]);
source_core_indices.push_back(kept_core_indices[static_cast<size_t>(index)]);
}
final_poses_3d[i] = merge_group(poses, options.min_match_score, prepared.internal_cameras.size());
final_poses_3d[i] = merge_group(poses, options.min_match_score, prepared.internal_cameras->size());
trace.merge.group_proposal_indices.push_back(std::move(source_core_indices));
trace.merge.merged_poses.push_back(final_poses_3d[i]);
}
std::vector<FinalAssociationState> group_associations(groups.size());
if (previous_poses_3d != nullptr)
{
for (size_t group_index = 0; group_index < trace.merge.group_proposal_indices.size(); ++group_index)
{
FinalAssociationState association;
std::set<int> candidate_previous_indices;
std::set<int64_t> candidate_previous_track_ids;
for (const int core_index : trace.merge.group_proposal_indices[group_index])
{
if (core_index < 0 || static_cast<size_t>(core_index) >= trace.core_proposals.size())
{
continue;
}
const int pair_index = trace.core_proposals[static_cast<size_t>(core_index)].pair_index;
if (pair_index < 0 || static_cast<size_t>(pair_index) >= trace.previous_filter.matches.size())
{
continue;
}
const PreviousPoseMatch &match = trace.previous_filter.matches[static_cast<size_t>(pair_index)];
if (!match.kept || match.previous_pose_index < 0 || match.previous_track_id < 0)
{
continue;
}
candidate_previous_indices.insert(match.previous_pose_index);
candidate_previous_track_ids.insert(match.previous_track_id);
}
association.candidate_previous_indices.assign(
candidate_previous_indices.begin(), candidate_previous_indices.end());
association.candidate_previous_track_ids.assign(
candidate_previous_track_ids.begin(), candidate_previous_track_ids.end());
if (association.candidate_previous_track_ids.empty())
{
association.status = AssociationStatus::New;
}
else if (association.candidate_previous_track_ids.size() == 1 &&
association.candidate_previous_indices.size() == 1)
{
association.status = AssociationStatus::Matched;
association.resolved_previous_index = association.candidate_previous_indices.front();
association.resolved_previous_track_id = association.candidate_previous_track_ids.front();
}
else
{
association.status = AssociationStatus::Ambiguous;
}
group_associations[group_index] = std::move(association);
}
}
add_extra_joints(final_poses_3d, joint_names);
filter_poses(final_poses_3d, roomparams, prepared.core_joint_idx, prepared.core_limbs_idx);
add_missing_joints(final_poses_3d, joint_names, options.min_match_score);
@@ -921,10 +955,20 @@ TriangulationTrace triangulate_debug_impl(
trace.final_poses.num_persons = valid_persons;
trace.final_poses.data.resize(valid_persons * trace.final_poses.num_joints * 4);
trace.association.pose_previous_indices.reserve(valid_persons);
trace.association.pose_previous_track_ids.reserve(valid_persons);
trace.association.pose_status.reserve(valid_persons);
trace.association.pose_candidate_previous_indices.reserve(valid_persons);
trace.association.pose_candidate_previous_track_ids.reserve(valid_persons);
trace.final_pose_associations.reserve(valid_persons);
std::set<int> resolved_previous_indices;
std::set<int64_t> resolved_previous_track_ids;
size_t person_index = 0;
for (const auto &pose : final_poses_3d)
for (size_t group_index = 0; group_index < final_poses_3d.size(); ++group_index)
{
const auto &pose = final_poses_3d[group_index];
const bool is_valid = std::any_of(
pose.begin(),
pose.end(),
@@ -944,9 +988,70 @@ TriangulationTrace triangulate_debug_impl(
trace.final_poses.at(person_index, joint, coord) = pose[joint][coord];
}
}
if (previous_poses_3d != nullptr)
{
const FinalAssociationState &association = group_associations[group_index];
trace.association.pose_previous_indices.push_back(association.resolved_previous_index);
trace.association.pose_previous_track_ids.push_back(association.resolved_previous_track_id);
trace.association.pose_status.push_back(association.status);
trace.association.pose_candidate_previous_indices.push_back(association.candidate_previous_indices);
trace.association.pose_candidate_previous_track_ids.push_back(
association.candidate_previous_track_ids);
if (association.status == AssociationStatus::Matched)
{
resolved_previous_indices.insert(association.resolved_previous_index);
resolved_previous_track_ids.insert(association.resolved_previous_track_id);
}
else if (association.status == AssociationStatus::New)
{
trace.association.new_pose_indices.push_back(static_cast<int>(person_index));
}
else if (association.status == AssociationStatus::Ambiguous)
{
trace.association.ambiguous_pose_indices.push_back(static_cast<int>(person_index));
}
FinalPoseAssociationDebug debug_association;
debug_association.final_pose_index = static_cast<int>(person_index);
debug_association.source_core_proposal_indices =
trace.merge.group_proposal_indices[group_index];
debug_association.candidate_previous_indices = association.candidate_previous_indices;
debug_association.candidate_previous_track_ids = association.candidate_previous_track_ids;
debug_association.resolved_previous_index = association.resolved_previous_index;
debug_association.resolved_previous_track_id = association.resolved_previous_track_id;
debug_association.status = association.status;
debug_association.source_pair_indices.reserve(debug_association.source_core_proposal_indices.size());
for (const int core_index : debug_association.source_core_proposal_indices)
{
if (core_index >= 0 && static_cast<size_t>(core_index) < trace.core_proposals.size())
{
debug_association.source_pair_indices.push_back(
trace.core_proposals[static_cast<size_t>(core_index)].pair_index);
}
}
trace.final_pose_associations.push_back(std::move(debug_association));
}
++person_index;
}
if (previous_poses_3d != nullptr)
{
for (size_t previous_index = 0; previous_index < previous_poses_3d->num_persons; ++previous_index)
{
const int previous_index_int = static_cast<int>(previous_index);
const int64_t track_id = previous_poses_3d->track_id(previous_index);
if (!resolved_previous_indices.contains(previous_index_int) &&
!resolved_previous_track_ids.contains(track_id))
{
trace.association.unmatched_previous_indices.push_back(previous_index_int);
trace.association.unmatched_previous_track_ids.push_back(track_id);
}
}
}
return trace;
}
@@ -954,13 +1059,10 @@ PreviousPoseFilterDebug filter_pairs_with_previous_poses_impl(
const PoseBatch2DView &poses_2d,
const std::vector<Camera> &cameras,
const std::vector<std::string> &joint_names,
const PoseBatch3DView &previous_poses_3d,
const TrackedPoseBatch3DView &previous_poses_3d,
const TriangulationOptions &options)
{
if (previous_poses_3d.num_persons > 0 && previous_poses_3d.num_joints != joint_names.size())
{
throw std::invalid_argument("previous_poses_3d must use the same joint count as joint_names.");
}
validate_previous_tracks(previous_poses_3d, joint_names);
PreparedInputs prepared = prepare_inputs(poses_2d, cameras, joint_names);
const std::vector<PairCandidate> pairs = build_pair_candidates_from_packed(prepared.packed_poses);
@@ -973,7 +1075,7 @@ PreviousPoseFilterDebug filter_pairs_with_previous_poses_impl(
return filter_pairs_with_previous_poses_impl(
prepared.packed_poses,
prepared.internal_cameras,
*prepared.internal_cameras,
prepared.core_joint_idx,
pairs,
options,
@@ -982,7 +1084,7 @@ PreviousPoseFilterDebug filter_pairs_with_previous_poses_impl(
std::tuple<std::vector<Pose2D>, std::vector<std::vector<float>>> project_poses(
const std::vector<Pose3D> &poses_3d,
const CachedCamera &icam,
const Camera &icam,
bool calc_dists)
{
if (poses_3d.empty())
@@ -998,7 +1100,7 @@ std::tuple<std::vector<Pose2D>, std::vector<std::vector<float>>> project_poses(
const std::array<std::array<float, 3>, 3> &K = icam.newK;
const std::array<std::array<float, 3>, 3> &R = icam.invR;
const std::array<std::array<float, 1>, 3> &T = icam.cam.T;
const std::array<std::array<float, 1>, 3> &T = icam.T;
for (size_t i = 0; i < num_persons; ++i)
{
@@ -1037,7 +1139,7 @@ std::tuple<std::vector<Pose2D>, std::vector<std::vector<float>>> project_poses(
v = (K[1][0] * x_cam + K[1][1] * y_cam + K[1][2] * z_cam) / z_cam;
}
if (u < 0.0f || u >= icam.cam.width || v < 0.0f || v >= icam.cam.height)
if (u < 0.0f || u >= icam.width || v < 0.0f || v >= icam.height)
{
u = 0.0f;
v = 0.0f;
@@ -1155,19 +1257,19 @@ std::array<float, 3> mat_mul_vec(
return res;
}
std::array<float, 3> calc_ray_dir(const CachedCamera &icam, const std::array<float, 2> &pt)
std::array<float, 3> calc_ray_dir(const Camera &icam, const std::array<float, 2> &pt)
{
// Compute normalized ray direction from the point
std::array<float, 3> uv1 = {pt[0], pt[1], 1.0};
auto d = mat_mul_vec(icam.cam.R, mat_mul_vec(icam.invK, uv1));
auto d = mat_mul_vec(icam.R, mat_mul_vec(icam.invK, uv1));
auto ray_dir = normalize(d);
return ray_dir;
}
std::array<float, 4> triangulate_midpoint(
const CachedCamera &icam1,
const CachedCamera &icam2,
const Camera &icam1,
const Camera &icam2,
const std::array<float, 2> &pt1,
const std::array<float, 2> &pt2)
{
@@ -1206,8 +1308,8 @@ std::array<float, 4> triangulate_midpoint(
std::pair<std::vector<std::array<float, 4>>, float> triangulate_and_score(
const std::vector<std::array<float, 3>> &pose1,
const std::vector<std::array<float, 3>> &pose2,
const CachedCamera &cam1,
const CachedCamera &cam2,
const Camera &cam1,
const Camera &cam2,
const std::array<std::array<float, 3>, 2> &roomparams,
const std::vector<std::array<size_t, 2>> &core_limbs_idx)
{
@@ -1307,7 +1409,7 @@ std::pair<std::vector<std::array<float, 4>>, float> triangulate_and_score(
auto dists2 = dists2s[0];
// Calculate scores for each view
float iscale = (cam1.cam.width + cam1.cam.height) / 2.0;
float iscale = (cam1.width + cam1.height) / 2.0f;
std::vector<float> score1 = score_projection(pose1, repro1, dists1, mask, iscale);
std::vector<float> score2 = score_projection(pose2, repro2, dists2, mask, iscale);
@@ -2417,7 +2519,7 @@ std::vector<PairCandidate> build_pair_candidates(const PoseBatch2DView &poses_2d
PreviousPoseFilterDebug filter_pairs_with_previous_poses(
const PoseBatch2DView &poses_2d,
const TriangulationConfig &config,
const PoseBatch3DView &previous_poses_3d,
const TrackedPoseBatch3DView &previous_poses_3d,
const TriangulationOptions *options_override)
{
const TriangulationOptions &options =
@@ -2429,7 +2531,7 @@ PreviousPoseFilterDebug filter_pairs_with_previous_poses(
TriangulationTrace triangulate_debug(
const PoseBatch2DView &poses_2d,
const TriangulationConfig &config,
const PoseBatch3DView *previous_poses_3d,
const TrackedPoseBatch3DView *previous_poses_3d,
const TriangulationOptions *options_override)
{
const TriangulationOptions &options =
@@ -2441,8 +2543,20 @@ TriangulationTrace triangulate_debug(
PoseBatch3D triangulate_poses(
const PoseBatch2DView &poses_2d,
const TriangulationConfig &config,
const PoseBatch3DView *previous_poses_3d,
const TriangulationOptions *options_override)
{
return triangulate_debug(poses_2d, config, previous_poses_3d, options_override).final_poses;
return triangulate_debug(poses_2d, config, nullptr, options_override).final_poses;
}
TriangulationResult triangulate_with_report(
const PoseBatch2DView &poses_2d,
const TriangulationConfig &config,
const TrackedPoseBatch3DView &previous_poses_3d,
const TriangulationOptions *options_override)
{
TriangulationTrace trace = triangulate_debug(poses_2d, config, &previous_poses_3d, options_override);
return TriangulationResult {
std::move(trace.final_poses),
std::move(trace.association),
};
}
+143 -5
View File
@@ -4,10 +4,14 @@ from collections.abc import Sequence
from typing import TYPE_CHECKING
from ._core import (
AssociationReport,
AssociationStatus,
Camera,
CameraModel,
FinalPoseAssociationDebug,
TriangulationConfig,
TriangulationOptions,
TriangulationResult,
CoreProposalDebug,
FullProposalDebug,
GroupingDebug,
@@ -17,28 +21,83 @@ from ._core import (
PreviousPoseMatch,
ProposalGroupDebug,
TriangulationTrace,
build_pair_candidates,
filter_pairs_with_previous_poses,
triangulate_debug,
triangulate_poses,
build_pair_candidates as _build_pair_candidates,
filter_pairs_with_previous_poses as _filter_pairs_with_previous_poses,
make_camera as _make_camera,
triangulate_debug as _triangulate_debug,
triangulate_poses as _triangulate_poses,
triangulate_with_report as _triangulate_with_report,
)
if TYPE_CHECKING:
import numpy as np
import numpy.typing as npt
from ._helpers import CameraLike, PoseViewLike
from ._helpers import CameraLike, CameraModelLike, Matrix3x3Like, PoseViewLike, VectorLike
PoseArray2D = npt.NDArray[np.float32]
PoseArray3D = npt.NDArray[np.float32]
PersonCountArray = npt.NDArray[np.uint32]
TrackIdArray = npt.NDArray[np.int64]
Camera.__doc__ = """Immutable camera calibration with precomputed projection cache fields."""
TriangulationConfig.__doc__ = """Stable scene configuration used for triangulation."""
TriangulationOptions.__doc__ = """Score and grouping thresholds used by triangulation."""
TriangulationResult.__doc__ = """Tracked triangulation output containing poses and association metadata."""
AssociationReport.__doc__ = """Track-association summary for a tracked triangulation call."""
TriangulationTrace.__doc__ = """Full debug trace for triangulation, including pair, grouping, and association stages."""
def convert_cameras(cameras: "Sequence[CameraLike]") -> list[Camera]:
"""Normalize mapping-like camera inputs into immutable bound `Camera` instances."""
from ._helpers import convert_cameras as _convert_cameras
return _convert_cameras(cameras)
def make_camera(
name: str,
K: "Matrix3x3Like",
DC: "VectorLike",
R: "Matrix3x3Like",
T: "Sequence[Sequence[float]]",
width: int,
height: int,
model: "CameraModel | CameraModelLike",
) -> Camera:
"""Create an immutable camera and precompute its cached projection fields."""
from ._helpers import _coerce_camera_model, _coerce_distortion
camera_model = _coerce_camera_model(model)
return _make_camera(
name,
K,
_coerce_distortion(DC, camera_model),
R,
T,
width,
height,
camera_model,
)
def build_pair_candidates(
poses_2d: "PoseArray2D",
person_counts: "PersonCountArray",
) -> list[PairCandidate]:
"""Enumerate all cross-view person pairs implied by the padded 2D pose batch."""
return _build_pair_candidates(poses_2d, person_counts)
def pack_poses_2d(
views: "Sequence[PoseViewLike]", *, joint_count: int | None = None
) -> "tuple[npt.NDArray[np.float32], npt.NDArray[np.uint32]]":
"""Pack ragged per-view pose detections into the padded tensor expected by the core API."""
from ._helpers import pack_poses_2d as _pack_poses_2d
return _pack_poses_2d(views, joint_count=joint_count)
@@ -52,6 +111,8 @@ def make_triangulation_config(
min_match_score: float = 0.95,
min_group_size: int = 1,
) -> TriangulationConfig:
"""Build a triangulation config from cameras, room parameters, and joint names."""
from ._helpers import make_triangulation_config as _make_triangulation_config
return _make_triangulation_config(
@@ -63,11 +124,86 @@ def make_triangulation_config(
)
def filter_pairs_with_previous_poses(
poses_2d: "PoseArray2D",
person_counts: "PersonCountArray",
config: TriangulationConfig,
previous_poses_3d: "PoseArray3D",
previous_track_ids: "TrackIdArray",
) -> PreviousPoseFilterDebug:
"""Filter raw cross-view pairs against caller-owned previous 3D tracks."""
return _filter_pairs_with_previous_poses(
poses_2d,
person_counts,
config,
previous_poses_3d,
previous_track_ids,
)
def triangulate_debug(
poses_2d: "PoseArray2D",
person_counts: "PersonCountArray",
config: TriangulationConfig,
previous_poses_3d: "PoseArray3D | None" = None,
previous_track_ids: "TrackIdArray | None" = None,
) -> TriangulationTrace:
"""Run triangulation and return the full debug trace.
If previous-frame 3D tracks are supplied, `previous_track_ids` must be supplied as an
aligned `int64` array of the same length.
"""
if previous_poses_3d is None:
return _triangulate_debug(poses_2d, person_counts, config)
if previous_track_ids is None:
raise ValueError("previous_track_ids is required when previous_poses_3d is provided.")
return _triangulate_debug(poses_2d, person_counts, config, previous_poses_3d, previous_track_ids)
def triangulate_poses(
poses_2d: "PoseArray2D",
person_counts: "PersonCountArray",
config: TriangulationConfig,
) -> "PoseArray3D":
"""Triangulate a frame into anonymous 3D poses without track association."""
return _triangulate_poses(poses_2d, person_counts, config)
def triangulate_with_report(
poses_2d: "PoseArray2D",
person_counts: "PersonCountArray",
config: TriangulationConfig,
previous_poses_3d: "PoseArray3D",
previous_track_ids: "TrackIdArray",
) -> TriangulationResult:
"""Triangulate a frame and return caller-owned track association results.
The previous-frame poses and IDs are treated as immutable caller state. The returned
association report classifies each final pose as matched, new, or ambiguous, and lists
unmatched previous tracks as deletion candidates.
"""
return _triangulate_with_report(
poses_2d,
person_counts,
config,
previous_poses_3d,
previous_track_ids,
)
__all__ = [
"Camera",
"CameraModel",
"AssociationReport",
"AssociationStatus",
"FinalPoseAssociationDebug",
"TriangulationConfig",
"TriangulationOptions",
"TriangulationResult",
"CoreProposalDebug",
"FullProposalDebug",
"GroupingDebug",
@@ -80,8 +216,10 @@ __all__ = [
"build_pair_candidates",
"convert_cameras",
"filter_pairs_with_previous_poses",
"make_camera",
"make_triangulation_config",
"pack_poses_2d",
"triangulate_debug",
"triangulate_poses",
"triangulate_with_report",
]
+115
View File
@@ -0,0 +1,115 @@
from collections.abc import Sequence
from typing import TypeAlias, overload
import numpy as np
import numpy.typing as npt
from ._core import (
AssociationReport,
AssociationStatus,
Camera,
CameraModel,
CoreProposalDebug,
FinalPoseAssociationDebug,
FullProposalDebug,
GroupingDebug,
MergeDebug,
PairCandidate,
PreviousPoseFilterDebug,
PreviousPoseMatch,
ProposalGroupDebug,
TriangulationConfig,
TriangulationOptions,
TriangulationResult,
TriangulationTrace,
)
from ._helpers import CameraLike, CameraModelLike, Matrix3x3Like, PoseViewLike, RoomParamsLike, VectorLike
PoseArray2D: TypeAlias = npt.NDArray[np.float32]
PoseArray3D: TypeAlias = npt.NDArray[np.float32]
PersonCountArray: TypeAlias = npt.NDArray[np.uint32]
TrackIdArray: TypeAlias = npt.NDArray[np.int64]
def convert_cameras(cameras: Sequence[CameraLike]) -> list[Camera]: ...
def make_camera(
name: str,
K: Matrix3x3Like,
DC: VectorLike,
R: Matrix3x3Like,
T: Sequence[Sequence[float]],
width: int,
height: int,
model: CameraModel | CameraModelLike,
) -> Camera: ...
def build_pair_candidates(
poses_2d: PoseArray2D,
person_counts: PersonCountArray,
) -> list[PairCandidate]: ...
def pack_poses_2d(
views: Sequence[PoseViewLike],
*,
joint_count: int | None = None,
) -> tuple[npt.NDArray[np.float32], npt.NDArray[np.uint32]]: ...
def make_triangulation_config(
cameras: Sequence[CameraLike],
roomparams: RoomParamsLike,
joint_names: Sequence[str],
*,
min_match_score: float = 0.95,
min_group_size: int = 1,
) -> TriangulationConfig: ...
def filter_pairs_with_previous_poses(
poses_2d: PoseArray2D,
person_counts: PersonCountArray,
config: TriangulationConfig,
previous_poses_3d: PoseArray3D,
previous_track_ids: TrackIdArray,
) -> PreviousPoseFilterDebug: ...
@overload
def triangulate_debug(
poses_2d: PoseArray2D,
person_counts: PersonCountArray,
config: TriangulationConfig,
) -> TriangulationTrace: ...
@overload
def triangulate_debug(
poses_2d: PoseArray2D,
person_counts: PersonCountArray,
config: TriangulationConfig,
previous_poses_3d: PoseArray3D,
previous_track_ids: TrackIdArray,
) -> TriangulationTrace: ...
def triangulate_poses(
poses_2d: PoseArray2D,
person_counts: PersonCountArray,
config: TriangulationConfig,
) -> PoseArray3D: ...
def triangulate_with_report(
poses_2d: PoseArray2D,
person_counts: PersonCountArray,
config: TriangulationConfig,
previous_poses_3d: PoseArray3D,
previous_track_ids: TrackIdArray,
) -> TriangulationResult: ...
__all__: list[str]
+13 -11
View File
@@ -6,7 +6,7 @@ from typing import Literal, TypeAlias, TypedDict
import numpy as np
import numpy.typing as npt
from ._core import Camera, CameraModel, TriangulationConfig, TriangulationOptions
from ._core import Camera, CameraModel, TriangulationConfig, TriangulationOptions, make_camera
Matrix3x3Like: TypeAlias = Sequence[Sequence[float]]
VectorLike: TypeAlias = Sequence[float]
@@ -64,17 +64,19 @@ def convert_cameras(cameras: Sequence[CameraLike]) -> list[Camera]:
converted.append(cam)
continue
camera = Camera()
camera.name = str(cam["name"])
camera.K = cam["K"]
camera_model = _coerce_camera_model(cam.get("model", cam.get("type", "pinhole")))
camera.DC = _coerce_distortion(cam["DC"], camera_model)
camera.R = cam["R"]
camera.T = cam["T"]
camera.width = int(cam["width"])
camera.height = int(cam["height"])
camera.model = camera_model
converted.append(camera)
converted.append(
make_camera(
str(cam["name"]),
cam["K"],
_coerce_distortion(cam["DC"], camera_model),
cam["R"],
cam["T"],
int(cam["width"]),
int(cam["height"]),
camera_model,
)
)
return converted
+70 -11
View File
@@ -51,15 +51,16 @@ def make_config(cameras, roomparams) -> rpt.TriangulationConfig:
def test_camera_structure_repr():
camera = rpt.Camera()
camera.name = "Camera 1"
camera.K = [[1, 0, 0], [0, 1, 0], [0, 0, 1]]
camera.DC = [0, 0, 0, 0, 0]
camera.R = [[1, 0, 0], [0, 1, 0], [0, 0, 1]]
camera.T = [[1], [2], [3]]
camera.width = 640
camera.height = 480
camera.model = rpt.CameraModel.PINHOLE
camera = rpt.make_camera(
"Camera 1",
[[1, 0, 0], [0, 1, 0], [0, 0, 1]],
[0, 0, 0, 0, 0],
[[1, 0, 0], [0, 1, 0], [0, 0, 1]],
[[1], [2], [3]],
640,
480,
rpt.CameraModel.PINHOLE,
)
rendered = repr(camera)
assert "Camera 1" in rendered
@@ -118,11 +119,19 @@ def test_triangulate_accepts_empty_previous_poses():
poses_2d, person_counts, cameras = load_case("data/p1/sample.json", "tests/poses_p1.json")
config = make_config(cameras, [[5.6, 6.4, 2.4], [0.0, -0.5, 1.2]])
empty_previous = np.zeros((0, len(JOINT_NAMES), 4), dtype=np.float32)
empty_previous_ids = np.zeros((0,), dtype=np.int64)
baseline = rpt.triangulate_poses(poses_2d, person_counts, config)
with_previous = rpt.triangulate_poses(poses_2d, person_counts, config, empty_previous)
result = rpt.triangulate_with_report(
poses_2d,
person_counts,
config,
empty_previous,
empty_previous_ids,
)
np.testing.assert_allclose(with_previous, baseline, rtol=1e-5, atol=1e-5)
np.testing.assert_allclose(result.poses_3d, baseline, rtol=1e-5, atol=1e-5)
assert result.association.unmatched_previous_track_ids == []
def test_triangulate_debug_matches_final_output():
@@ -134,6 +143,7 @@ def test_triangulate_debug_matches_final_output():
np.testing.assert_allclose(trace.final_poses, final_poses, rtol=1e-5, atol=1e-5)
assert len(trace.pairs) >= len(trace.core_proposals)
assert trace.association.pose_previous_track_ids == []
for group in trace.grouping.groups:
assert all(0 <= index < len(trace.core_proposals) for index in group.proposal_indices)
for merge_indices in trace.merge.group_proposal_indices:
@@ -144,18 +154,67 @@ def test_filter_pairs_with_previous_poses_returns_debug_matches():
poses_2d, person_counts, cameras = load_case("data/p1/sample.json", "tests/poses_p1.json")
config = make_config(cameras, [[5.6, 6.4, 2.4], [0.0, -0.5, 1.2]])
previous_poses = rpt.triangulate_poses(poses_2d, person_counts, config)
previous_track_ids = np.arange(previous_poses.shape[0], dtype=np.int64) + 100
debug = rpt.filter_pairs_with_previous_poses(
poses_2d,
person_counts,
config,
previous_poses,
previous_track_ids,
)
assert debug.used_previous_poses is True
assert len(debug.matches) == len(rpt.build_pair_candidates(poses_2d, person_counts))
assert len(debug.kept_pairs) == len(debug.kept_pair_indices)
assert any(match.matched_view1 or match.matched_view2 for match in debug.matches)
assert any(match.previous_track_id >= 100 for match in debug.matches if match.previous_pose_index >= 0)
def test_triangulate_with_report_resolves_previous_track_ids():
poses_2d, person_counts, cameras = load_case("data/p1/sample.json", "tests/poses_p1.json")
config = make_config(cameras, [[5.6, 6.4, 2.4], [0.0, -0.5, 1.2]])
previous_poses = rpt.triangulate_poses(poses_2d, person_counts, config)
previous_track_ids = np.arange(previous_poses.shape[0], dtype=np.int64) + 100
result = rpt.triangulate_with_report(
poses_2d,
person_counts,
config,
previous_poses,
previous_track_ids,
)
assert result.poses_3d.shape == previous_poses.shape
assert len(result.association.pose_previous_track_ids) == result.poses_3d.shape[0]
matched_track_ids = sorted(
track_id for track_id in result.association.pose_previous_track_ids if track_id >= 0
)
unmatched_track_ids = sorted(result.association.unmatched_previous_track_ids)
for pose_index in result.association.new_pose_indices:
assert result.association.pose_previous_track_ids[pose_index] == -1
for pose_index in result.association.ambiguous_pose_indices:
assert result.association.pose_previous_track_ids[pose_index] == -1
assert matched_track_ids == sorted(set(matched_track_ids))
assert sorted(matched_track_ids + unmatched_track_ids) == list(previous_track_ids)
def test_triangulate_with_report_rejects_duplicate_previous_track_ids():
poses_2d, person_counts, cameras = load_case("data/p1/sample.json", "tests/poses_p1.json")
config = make_config(cameras, [[5.6, 6.4, 2.4], [0.0, -0.5, 1.2]])
previous_poses = rpt.triangulate_poses(poses_2d, person_counts, config)
duplicate_ids = np.zeros((previous_poses.shape[0],), dtype=np.int64)
with pytest.raises(ValueError, match="unique"):
rpt.triangulate_with_report(
poses_2d,
person_counts,
config,
previous_poses,
duplicate_ids,
)
def test_triangulate_does_not_mutate_inputs():