diff --git a/include/basalt/optical_flow/frame_to_frame_optical_flow.h b/include/basalt/optical_flow/frame_to_frame_optical_flow.h index 9fd0814..530c645 100644 --- a/include/basalt/optical_flow/frame_to_frame_optical_flow.h +++ b/include/basalt/optical_flow/frame_to_frame_optical_flow.h @@ -116,7 +116,7 @@ class FrameToFrameOpticalFlow : public OpticalFlowBase { transforms->observations.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()), @@ -138,7 +138,7 @@ class FrameToFrameOpticalFlow : 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) { @@ -174,8 +174,8 @@ class FrameToFrameOpticalFlow : public OpticalFlowBase { frame_counter++; } - void trackPoints(const basalt::ManagedImagePyr& pyr_1, - const basalt::ManagedImagePyr& pyr_2, + void trackPoints(const basalt::ManagedImagePyr& pyr_1, + const basalt::ManagedImagePyr& pyr_2, const Eigen::aligned_map& transform_map_1, Eigen::aligned_map& @@ -260,7 +260,7 @@ class FrameToFrameOpticalFlow : 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; @@ -381,7 +381,7 @@ class FrameToFrameOpticalFlow : public OpticalFlowBase { basalt::Calibration calib; OpticalFlowResult::Ptr transforms; - std::shared_ptr>> old_pyramid, + std::shared_ptr>> old_pyramid, pyramid; Matrix4 E; diff --git a/include/basalt/optical_flow/patch_optical_flow.h b/include/basalt/optical_flow/patch_optical_flow.h index 51ead8b..c99516b 100644 --- a/include/basalt/optical_flow/patch_optical_flow.h +++ b/include/basalt/optical_flow/patch_optical_flow.h @@ -116,7 +116,7 @@ class PatchOpticalFlow : public OpticalFlowBase { transforms->observations.resize(calib.intrinsics.size()); transforms->t_ns = t_ns; - pyramid.reset(new std::vector>); + pyramid.reset(new std::vector>); pyramid->resize(calib.intrinsics.size()); for (size_t i = 0; i < calib.intrinsics.size(); i++) { pyramid->at(i).setFromImage(*new_img_vec->img_data[i].img, @@ -133,7 +133,7 @@ class PatchOpticalFlow : public OpticalFlowBase { old_pyramid = pyramid; - pyramid.reset(new std::vector>); + pyramid.reset(new std::vector>); pyramid->resize(calib.intrinsics.size()); for (size_t i = 0; i < calib.intrinsics.size(); i++) { pyramid->at(i).setFromImage(*new_img_vec->img_data[i].img, @@ -164,8 +164,8 @@ class PatchOpticalFlow : public OpticalFlowBase { frame_counter++; } - void trackPoints(const basalt::ManagedImagePyr& pyr_1, - const basalt::ManagedImagePyr& pyr_2, + void trackPoints(const basalt::ManagedImagePyr& pyr_1, + const basalt::ManagedImagePyr& pyr_2, const Eigen::aligned_map& transform_map_1, Eigen::aligned_map& @@ -246,7 +246,7 @@ class PatchOpticalFlow : 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; @@ -380,7 +380,7 @@ class PatchOpticalFlow : public OpticalFlowBase { patches; OpticalFlowResult::Ptr transforms; - std::shared_ptr>> old_pyramid, + std::shared_ptr>> old_pyramid, pyramid; Eigen::Matrix4d E; diff --git a/include/basalt/utils/vis_utils.h b/include/basalt/utils/vis_utils.h index fe2db28..a43d7fd 100644 --- a/include/basalt/utils/vis_utils.h +++ b/include/basalt/utils/vis_utils.h @@ -40,13 +40,13 @@ OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #include -const u_int8_t cam_color[3]{250, 0, 26}; -const u_int8_t state_color[3]{250, 0, 26}; -const u_int8_t pose_color[3]{0, 50, 255}; -const u_int8_t gt_color[3]{0, 171, 47}; +const uint8_t cam_color[3]{250, 0, 26}; +const uint8_t state_color[3]{250, 0, 26}; +const uint8_t pose_color[3]{0, 50, 255}; +const uint8_t gt_color[3]{0, 171, 47}; inline void render_camera(const Eigen::Matrix4d& T_w_c, float lineWidth, - const u_int8_t* color, float sizeFactor) { + const uint8_t* color, float sizeFactor) { const float sz = sizeFactor; const float width = 640, height = 480, fx = 500, fy = 500, cx = 320, cy = 240;