fix stdint types

This commit is contained in:
Vladyslav Usenko 2021-05-01 10:45:08 +02:00
parent c7ceee72c0
commit 7477c4a0f0
3 changed files with 17 additions and 17 deletions

View File

@ -116,7 +116,7 @@ class FrameToFrameOpticalFlow : public OpticalFlowBase {
transforms->observations.resize(calib.intrinsics.size()); transforms->observations.resize(calib.intrinsics.size());
transforms->t_ns = t_ns; 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()); pyramid->resize(calib.intrinsics.size());
tbb::parallel_for(tbb::blocked_range<size_t>(0, calib.intrinsics.size()), tbb::parallel_for(tbb::blocked_range<size_t>(0, calib.intrinsics.size()),
@ -138,7 +138,7 @@ class FrameToFrameOpticalFlow : public OpticalFlowBase {
old_pyramid = pyramid; 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()); pyramid->resize(calib.intrinsics.size());
tbb::parallel_for(tbb::blocked_range<size_t>(0, calib.intrinsics.size()), tbb::parallel_for(tbb::blocked_range<size_t>(0, calib.intrinsics.size()),
[&](const tbb::blocked_range<size_t>& r) { [&](const tbb::blocked_range<size_t>& r) {
@ -174,8 +174,8 @@ class FrameToFrameOpticalFlow : public OpticalFlowBase {
frame_counter++; frame_counter++;
} }
void trackPoints(const basalt::ManagedImagePyr<u_int16_t>& pyr_1, void trackPoints(const basalt::ManagedImagePyr<uint16_t>& pyr_1,
const basalt::ManagedImagePyr<u_int16_t>& pyr_2, const basalt::ManagedImagePyr<uint16_t>& pyr_2,
const Eigen::aligned_map<KeypointId, Eigen::AffineCompact2f>& const Eigen::aligned_map<KeypointId, Eigen::AffineCompact2f>&
transform_map_1, transform_map_1,
Eigen::aligned_map<KeypointId, Eigen::AffineCompact2f>& Eigen::aligned_map<KeypointId, Eigen::AffineCompact2f>&
@ -260,7 +260,7 @@ class FrameToFrameOpticalFlow : public OpticalFlowBase {
return patch_valid; 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, const PatchT& dp,
Eigen::AffineCompact2f& transform) const { Eigen::AffineCompact2f& transform) const {
bool patch_valid = true; bool patch_valid = true;
@ -381,7 +381,7 @@ class FrameToFrameOpticalFlow : public OpticalFlowBase {
basalt::Calibration<Scalar> calib; basalt::Calibration<Scalar> calib;
OpticalFlowResult::Ptr transforms; 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; pyramid;
Matrix4 E; Matrix4 E;

View File

@ -116,7 +116,7 @@ class PatchOpticalFlow : public OpticalFlowBase {
transforms->observations.resize(calib.intrinsics.size()); transforms->observations.resize(calib.intrinsics.size());
transforms->t_ns = t_ns; 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()); pyramid->resize(calib.intrinsics.size());
for (size_t i = 0; i < calib.intrinsics.size(); i++) { for (size_t i = 0; i < calib.intrinsics.size(); i++) {
pyramid->at(i).setFromImage(*new_img_vec->img_data[i].img, pyramid->at(i).setFromImage(*new_img_vec->img_data[i].img,
@ -133,7 +133,7 @@ class PatchOpticalFlow : public OpticalFlowBase {
old_pyramid = pyramid; 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()); pyramid->resize(calib.intrinsics.size());
for (size_t i = 0; i < calib.intrinsics.size(); i++) { for (size_t i = 0; i < calib.intrinsics.size(); i++) {
pyramid->at(i).setFromImage(*new_img_vec->img_data[i].img, pyramid->at(i).setFromImage(*new_img_vec->img_data[i].img,
@ -164,8 +164,8 @@ class PatchOpticalFlow : public OpticalFlowBase {
frame_counter++; frame_counter++;
} }
void trackPoints(const basalt::ManagedImagePyr<u_int16_t>& pyr_1, void trackPoints(const basalt::ManagedImagePyr<uint16_t>& pyr_1,
const basalt::ManagedImagePyr<u_int16_t>& pyr_2, const basalt::ManagedImagePyr<uint16_t>& pyr_2,
const Eigen::aligned_map<KeypointId, Eigen::AffineCompact2f>& const Eigen::aligned_map<KeypointId, Eigen::AffineCompact2f>&
transform_map_1, transform_map_1,
Eigen::aligned_map<KeypointId, Eigen::AffineCompact2f>& Eigen::aligned_map<KeypointId, Eigen::AffineCompact2f>&
@ -246,7 +246,7 @@ class PatchOpticalFlow : public OpticalFlowBase {
return patch_valid; 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, const PatchT& dp,
Eigen::AffineCompact2f& transform) const { Eigen::AffineCompact2f& transform) const {
bool patch_valid = true; bool patch_valid = true;
@ -380,7 +380,7 @@ class PatchOpticalFlow : public OpticalFlowBase {
patches; patches;
OpticalFlowResult::Ptr transforms; 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; pyramid;
Eigen::Matrix4d E; Eigen::Matrix4d E;

View File

@ -40,13 +40,13 @@ OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
#include <basalt/utils/sophus_utils.hpp> #include <basalt/utils/sophus_utils.hpp>
const u_int8_t cam_color[3]{250, 0, 26}; const uint8_t cam_color[3]{250, 0, 26};
const u_int8_t state_color[3]{250, 0, 26}; const uint8_t state_color[3]{250, 0, 26};
const u_int8_t pose_color[3]{0, 50, 255}; const uint8_t pose_color[3]{0, 50, 255};
const u_int8_t gt_color[3]{0, 171, 47}; const uint8_t gt_color[3]{0, 171, 47};
inline void render_camera(const Eigen::Matrix4d& T_w_c, float lineWidth, 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 sz = sizeFactor;
const float width = 640, height = 480, fx = 500, fy = 500, cx = 320, cy = 240; const float width = 640, height = 480, fx = 500, fy = 500, cx = 320, cy = 240;