multiframe optical flow: u_int16_t --> uint16_t

This commit is contained in:
Nikolaus Demmel 2021-12-03 16:11:27 +01:00
parent 99321d1af3
commit bfeda2affa
1 changed files with 6 additions and 6 deletions

View File

@ -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<basalt::ManagedImagePyr<u_int16_t>>);
pyramid.reset(new std::vector<basalt::ManagedImagePyr<uint16_t>>);
pyramid->resize(calib.intrinsics.size());
tbb::parallel_for(tbb::blocked_range<size_t>(0, calib.intrinsics.size()),
@ -143,7 +143,7 @@ class MultiscaleFrameToFrameOpticalFlow : public OpticalFlowBase {
old_pyramid = pyramid;
pyramid.reset(new std::vector<basalt::ManagedImagePyr<u_int16_t>>);
pyramid.reset(new std::vector<basalt::ManagedImagePyr<uint16_t>>);
pyramid->resize(calib.intrinsics.size());
tbb::parallel_for(tbb::blocked_range<size_t>(0, calib.intrinsics.size()),
[&](const tbb::blocked_range<size_t>& r) {
@ -191,8 +191,8 @@ class MultiscaleFrameToFrameOpticalFlow : public OpticalFlowBase {
}
void trackPoints(
const basalt::ManagedImagePyr<u_int16_t>& pyr_1,
const basalt::ManagedImagePyr<u_int16_t>& pyr_2,
const basalt::ManagedImagePyr<uint16_t>& pyr_1,
const basalt::ManagedImagePyr<uint16_t>& pyr_2,
const Eigen::aligned_map<KeypointId, Eigen::AffineCompact2f>&
transform_map_1,
const std::map<KeypointId, size_t>& pyramid_levels_1,
@ -301,7 +301,7 @@ class MultiscaleFrameToFrameOpticalFlow : public OpticalFlowBase {
return patch_valid;
}
inline bool trackPointAtLevel(const Image<const u_int16_t>& img_2,
inline bool trackPointAtLevel(const Image<const uint16_t>& img_2,
const PatchT& dp,
Eigen::AffineCompact2f& transform) const {
bool patch_valid = true;
@ -444,7 +444,7 @@ class MultiscaleFrameToFrameOpticalFlow : public OpticalFlowBase {
basalt::Calibration<Scalar> calib;
OpticalFlowResult::Ptr transforms;
std::shared_ptr<std::vector<basalt::ManagedImagePyr<u_int16_t>>> old_pyramid,
std::shared_ptr<std::vector<basalt::ManagedImagePyr<uint16_t>>> old_pyramid,
pyramid;
// map from stereo pair -> essential matrix