From bfeda2affa16b538e7f3e09cacc81cf3208bc1ef Mon Sep 17 00:00:00 2001 From: Nikolaus Demmel Date: Fri, 3 Dec 2021 16:11:27 +0100 Subject: [PATCH] multiframe optical flow: u_int16_t --> uint16_t --- .../multiscale_frame_to_frame_optical_flow.h | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/include/basalt/optical_flow/multiscale_frame_to_frame_optical_flow.h b/include/basalt/optical_flow/multiscale_frame_to_frame_optical_flow.h index 5fda7f8..02d6132 100644 --- a/include/basalt/optical_flow/multiscale_frame_to_frame_optical_flow.h +++ b/include/basalt/optical_flow/multiscale_frame_to_frame_optical_flow.h @@ -122,7 +122,7 @@ class MultiscaleFrameToFrameOpticalFlow : public OpticalFlowBase { transforms->pyramid_levels.resize(calib.intrinsics.size()); transforms->t_ns = t_ns; - pyramid.reset(new std::vector>); + pyramid.reset(new std::vector>); pyramid->resize(calib.intrinsics.size()); tbb::parallel_for(tbb::blocked_range(0, calib.intrinsics.size()), @@ -143,7 +143,7 @@ class MultiscaleFrameToFrameOpticalFlow : public OpticalFlowBase { old_pyramid = pyramid; - pyramid.reset(new std::vector>); + pyramid.reset(new std::vector>); pyramid->resize(calib.intrinsics.size()); tbb::parallel_for(tbb::blocked_range(0, calib.intrinsics.size()), [&](const tbb::blocked_range& r) { @@ -191,8 +191,8 @@ class MultiscaleFrameToFrameOpticalFlow : public OpticalFlowBase { } void trackPoints( - const basalt::ManagedImagePyr& pyr_1, - const basalt::ManagedImagePyr& pyr_2, + const basalt::ManagedImagePyr& pyr_1, + const basalt::ManagedImagePyr& pyr_2, const Eigen::aligned_map& transform_map_1, const std::map& pyramid_levels_1, @@ -301,7 +301,7 @@ class MultiscaleFrameToFrameOpticalFlow : public OpticalFlowBase { return patch_valid; } - inline bool trackPointAtLevel(const Image& img_2, + inline bool trackPointAtLevel(const Image& img_2, const PatchT& dp, Eigen::AffineCompact2f& transform) const { bool patch_valid = true; @@ -444,7 +444,7 @@ class MultiscaleFrameToFrameOpticalFlow : public OpticalFlowBase { basalt::Calibration calib; OpticalFlowResult::Ptr transforms; - std::shared_ptr>> old_pyramid, + std::shared_ptr>> old_pyramid, pyramid; // map from stereo pair -> essential matrix