Skip to content

Commit

Permalink
Fix some of warnings...
Browse files Browse the repository at this point in the history
  • Loading branch information
xuhao1 committed Oct 23, 2024
1 parent c51ac15 commit ece2a40
Show file tree
Hide file tree
Showing 25 changed files with 67 additions and 66 deletions.
2 changes: 1 addition & 1 deletion camera_models/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
cmake_minimum_required(VERSION 2.8.3)
cmake_minimum_required(VERSION 3.0.0)
project(camera_models)

set(CMAKE_BUILD_TYPE "Release")
Expand Down
8 changes: 4 additions & 4 deletions d2common/include/d2common/d2frontend_types.h
Original file line number Diff line number Diff line change
Expand Up @@ -217,7 +217,7 @@ struct VisualImageDesc {
img_desc.landmark_descriptor_int8.resize(landmark_descriptor.size());
img_desc.landmark_descriptor_size = 0;
auto max = desc0.cwiseAbs().maxCoeff();
for (int i = 0; i < landmark_descriptor.size(); i++) {
for (unsigned int i = 0; i < landmark_descriptor.size(); i++) {
img_desc.landmark_descriptor_int8[i] = (int8_t)(desc0[i] / max * 127);
}
img_desc.landmark_scores_size = 0;
Expand Down Expand Up @@ -248,7 +248,7 @@ struct VisualImageDesc {
img_desc.header.image_desc_int8.resize(image_desc.size());
img_desc.header.image_desc_size = 0;
double max = Eigen::Map<const VectorXf>(image_desc.data(), image_desc.size()).cwiseAbs().maxCoeff();
for (int i = 0; i < image_desc.size(); i++) {
for (unsigned int i = 0; i < image_desc.size(); i++) {
img_desc.header.image_desc_int8[i] = (int8_t)(image_desc[i] / max * 127);
}
} else {
Expand Down Expand Up @@ -304,7 +304,7 @@ struct VisualImageDesc {
if (desc.landmark_descriptor_int8.size() > 0) {
landmark_descriptor.resize(desc.landmark_descriptor_int8.size());
Eigen::Map<VectorXf> desc0(landmark_descriptor.data(), landmark_descriptor.size());
for (int i = 0; i < landmark_descriptor.size(); i++) {
for (unsigned int i = 0; i < landmark_descriptor.size(); i++) {
desc0(i) = desc.landmark_descriptor_int8[i] / 127.0;
}
//Per feature normalize the landmark desc
Expand All @@ -317,7 +317,7 @@ struct VisualImageDesc {
if (desc.header.image_desc_size_int8 > 0) {
image_desc.resize(desc.header.image_desc_size_int8);
Eigen::Map<VectorXf> gdesc(image_desc.data(), image_desc.size());
for (int i = 0; i < image_desc.size(); i++) {
for (unsigned int i = 0; i < image_desc.size(); i++) {
gdesc(i) = desc.header.image_desc_int8[i] / 127.0;
}
gdesc.normalize();
Expand Down
3 changes: 2 additions & 1 deletion d2common/include/d2common/d2landmarks.h
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,7 @@
#include <opencv2/opencv.hpp>
#include "d2basetypes.h"
#include <swarm_msgs/swarm_lcm_converter.hpp>
#include <spdlog/spdlog.h>

namespace D2Common {
enum LandmarkFlag {
Expand Down Expand Up @@ -268,7 +269,7 @@ struct LandmarkPerId {
return it;
}
}
printf("LandmarkPerId::at: Error, cannot find frame_id %d\n", frame_id);
spdlog::warn("LandmarkPerId::at Warn, cannot find frame_id {}", frame_id);
return LandmarkPerFrame();
}

Expand Down
2 changes: 1 addition & 1 deletion d2common/include/d2common/fisheye_undistort.h
Original file line number Diff line number Diff line change
Expand Up @@ -129,7 +129,7 @@ class FisheyeUndist {
auto _photometics_gpu = undist_all_cuda(photomertic, true);
photometics = _photometics;
photometics_gpu = _photometics_gpu;
for (int i = 0; i < _photometics.size(); i++) {
for (unsigned int i = 0; i < _photometics.size(); i++) {
cv::Mat bgr;
cv::cvtColor(_photometics[i], bgr, cv::COLOR_GRAY2BGR);
photometics_bgr.push_back(bgr);
Expand Down
2 changes: 1 addition & 1 deletion d2common/include/d2common/integration_base.h
Original file line number Diff line number Diff line change
Expand Up @@ -88,7 +88,7 @@ class IntegrationBase
linearized_bg = _linearized_bg;
jacobian.setIdentity();
covariance.setZero();
for (int i = 0; i < static_cast<int>(dt_buf.size()); i++)
for (unsigned int i = 0; i < dt_buf.size(); i++)
propagate(dt_buf[i], acc_buf[i], gyr_buf[i]);
}

Expand Down
2 changes: 1 addition & 1 deletion d2common/src/d2vinsframe.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -99,7 +99,7 @@ swarm_msgs::VIOFrame VINSFrame::toROS(const std::vector<Swarm::Pose>& exts) {
msg.is_keyframe = is_keyframe;
msg.reference_frame_id = reference_frame_id;
msg.odom = odom.toRos();
for (int i = 0; i < exts.size(); i++) {
for (unsigned int i = 0; i < exts.size(); i++) {
msg.extrinsics.emplace_back(exts[i].toROS());
}
return msg;
Expand Down
4 changes: 2 additions & 2 deletions d2common/src/solver/BaseParamResInfo.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -61,7 +61,7 @@ void ResidualInfo::Evaluate(const std::vector<ParamInfo> &param_infos,
std::vector<int> blk_sizes = cost_function->parameter_block_sizes();
std::vector<double *> raw_jacobians(blk_sizes.size());
jacobians.resize(blk_sizes.size());
for (int i = 0; i < static_cast<int>(blk_sizes.size()); i++) {
for (unsigned int i = 0; i < blk_sizes.size(); i++) {
jacobians[i].resize(cost_function->num_residuals(), blk_sizes[i]);
jacobians[i].setZero();
raw_jacobians[i] = jacobians[i].data();
Expand All @@ -83,7 +83,7 @@ void ResidualInfo::Evaluate(const std::vector<ParamInfo> &param_infos,
residual_scaling_ = sqrt_rho1_ / (1 - alpha);
alpha_sq_norm_ = alpha / sq_norm;
}
for (int i = 0; i < static_cast<int>(params.size()); i++) {
for (unsigned int i = 0; i < params.size(); i++) {
jacobians[i] = sqrt_rho1_ * (jacobians[i] -
alpha_sq_norm_ * residuals *
(residuals.transpose() * jacobians[i]));
Expand Down
2 changes: 1 addition & 1 deletion d2frontend/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
cmake_minimum_required(VERSION 2.8.3)
cmake_minimum_required(VERSION 3.0.0)
project(d2frontend)

set(CMAKE_CXX_STANDARD 17)
Expand Down
2 changes: 1 addition & 1 deletion d2frontend/include/d2frontend/utils.h
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 +36,7 @@ Eigen::VectorXf load_csv_vec_eigen(std::string csv);
template <typename T, typename B>
inline void reduceVector(std::vector<T> &v, std::vector<B> status) {
int j = 0;
for (int i = 0; i < int(v.size()); i++)
for (unsigned int i = 0; i < v.size(); i++)
if (status[i])
v[j++] = v[i];
v.resize(j);
Expand Down
10 changes: 5 additions & 5 deletions d2frontend/src/CNN/superpoint.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -174,7 +174,7 @@ bool SuperPoint::infer(const cv::Mat & input, std::vector<cv::Point2f> & keypoin
}
// [n_keypoints_num,n]
for (auto &descriptor : raw_descriptors) {
for (int i = 0; i < descriptor.size(); ++i) {
for (unsigned int i = 0; i < descriptor.size(); ++i) {
descriptors.push_back(descriptor[i]);
}
}
Expand All @@ -201,7 +201,7 @@ bool SuperPoint::processInput(const tensorrt_buffer::BufferManager &buffers, con
void SuperPoint::findHighScoreIndex(std::vector<float> &scores, std::vector<Eigen::Vector2f> &keypoints,
int h, int w, float threshold) {
std::vector<float> new_scores;
for (int i = 0; i < scores.size(); ++i) {
for (unsigned int i = 0; i < scores.size(); ++i) {
if (scores[i] > threshold) {
Eigen::Vector2f location = {i % w, int(i / w)}; //u,v
keypoints.emplace_back(location);
Expand All @@ -217,7 +217,7 @@ void SuperPoint::removeBorders( std::vector<Eigen::Vector2f> &keypoints, std::ve
int width) {
std::vector<Eigen::Vector2f> keypoints_selected;
std::vector<float> scores_selected;
for (int i = 0; i < keypoints.size(); ++i) {
for (unsigned int i = 0; i < keypoints.size(); ++i) {
bool flag_h = (keypoints[i][1] >= border) && (keypoints[i][1] < (height - border)); //v
bool flag_w = (keypoints[i][0] >= border) && (keypoints[i][0] < (width - border)); //u
if (flag_h && flag_w) {
Expand Down Expand Up @@ -440,14 +440,14 @@ bool SuperPoint::deserializeEngine(){
// Eigen::Matrix<float, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor>
// _desc_new = (_desc.rowwise() - pca_mean) * pca_comp_T;
// // Perform row wise normalization
// for (int i = 0; i < _desc_new.rows(); i++) {
// for (unsigned int i = 0; i < _desc_new.rows(); i++) {
// _desc_new.row(i) /= _desc_new.row(i).norm();
// }
// local_descriptors = std::vector<float>(
// _desc_new.data(),
// _desc_new.data() + _desc_new.cols() * _desc_new.rows());
// } else {
// for (int i = 0; i < _desc.rows(); i++) {
// for (unsigned int i = 0; i < _desc.rows(); i++) {
// _desc.row(i) /= _desc.row(i).norm();
// }
// local_descriptors = std::vector<float>(
Expand Down
8 changes: 4 additions & 4 deletions d2frontend/src/CNN/superpoint_common.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@ void getKeyPoints(const cv::Mat& prob, float threshold, int nms_dist,
std::vector<cv::Point> kps;
cv::findNonZero(mask, kps);
std::vector<cv::Point2f> keypoints_no_nms;
for (int i = 0; i < kps.size(); i++) {
for (unsigned int i = 0; i < kps.size(); i++) {
keypoints_no_nms.push_back(cv::Point2f(kps[i].x, kps[i].y));
}

Expand Down Expand Up @@ -76,14 +76,14 @@ void computeDescriptors(const torch::Tensor& mProb, const torch::Tensor& mDesc,
Eigen::Matrix<float, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor>
_desc_new = (_desc.rowwise() - pca_mean) * pca_comp_T;
// Perform row wise normalization
for (int i = 0; i < _desc_new.rows(); i++) {
for (unsigned int i = 0; i < _desc_new.rows(); i++) {
_desc_new.row(i) /= _desc_new.row(i).norm();
}
local_descriptors = std::vector<float>(
_desc_new.data(),
_desc_new.data() + _desc_new.cols() * _desc_new.rows());
} else {
for (int i = 0; i < _desc.rows(); i++) {
for (unsigned int i = 0; i < _desc.rows(); i++) {
_desc.row(i) /= _desc.row(i).norm();
}
local_descriptors = std::vector<float>(
Expand Down Expand Up @@ -126,7 +126,7 @@ void NMS2(std::vector<cv::Point2f> det, cv::Mat conf,
confidence.at<float>(vv, uu) = conf.at<float>(i, 0);
}

for (int i = 0; i < pts_raw.size(); i++) {
for (unsigned int i = 0; i < pts_raw.size(); i++) {
int uu = (int)pts_raw[i].x;
int vv = (int)pts_raw[i].y;

Expand Down
22 changes: 11 additions & 11 deletions d2frontend/src/d2featuretracker.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -501,7 +501,7 @@ TrackReport D2FeatureTracker::trackLK(VisualImageDesc &frame) {
TrackLRType::WHOLE_IMG_MATCH);
pyr_has_built = true;
cur_lk_info.lk_pts_3d_norm.resize(cur_lk_info.lk_pts.size());
for (int i = 0; i < cur_lk_info.lk_pts.size(); i++) {
for (unsigned int i = 0; i < cur_lk_info.lk_pts.size(); i++) {
auto ret =
createLKLandmark(frame, cur_lk_info.lk_pts[i],
cur_lk_info.lk_ids[i], cur_lk_info.lk_types[i]);
Expand Down Expand Up @@ -723,7 +723,7 @@ TrackReport D2FeatureTracker::trackLK(const VisualImageDesc &left_frame,
keyframe_lk_infos.at(left_frame.frame_id).at(left_frame.camera_index);
// Add the SP points to the LK points if use_lk_for_left_right_track is true
if (use_lk_for_left_right_track && !_config.sp_track_use_lk) {
for (int i = 0; i < left_frame.landmarkNum(); i++) {
for (unsigned int i = 0; i < left_frame.landmarkNum(); i++) {
if (left_frame.landmarks[i].landmark_id >= 0 &&
left_frame.landmarks[i].type == LandmarkType::SuperPointLandmark) {
left_lk_info.lk_pts.emplace_back(left_frame.landmarks[i].pt2d);
Expand All @@ -745,7 +745,7 @@ TrackReport D2FeatureTracker::trackLK(const VisualImageDesc &left_frame,
if (!left_lk_info.lk_ids.empty()) {
auto cur_lk_info =
opticalflowTrackPyr(right_frame.raw_image, left_lk_info, type);
for (int i = 0; i < cur_lk_info.lk_pts.size(); i++) {
for (unsigned int i = 0; i < cur_lk_info.lk_pts.size(); i++) {
auto ret =
createLKLandmark(right_frame, cur_lk_info.lk_pts[i],
cur_lk_info.lk_ids[i], cur_lk_info.lk_types[i]);
Expand Down Expand Up @@ -952,7 +952,7 @@ cv::Mat D2FeatureTracker::drawToImage(const VisualImageDesc &frame,
// Draw predictions here
auto &predictions = landmark_predictions_viz.at(frame.camera_id);
auto &prev = landmark_predictions_matched_viz.at(frame.camera_id);
for (int i = 0; i < predictions.size(); i++) {
for (unsigned int i = 0; i < predictions.size(); i++) {
cv::circle(img, predictions[i], 3, cv::Scalar(0, 255, 0), 2);
cv::line(img, prev[i], predictions[i], cv::Scalar(0, 0, 255), 1, 8, 0);
// if (cv::norm(prev[i] - predictions[i]) > 20) {
Expand Down Expand Up @@ -1078,7 +1078,7 @@ std::pair<std::vector<float>, std::vector<cv::Point2f>> getFeatureHalfImg(
float move_cols =
params->width_undistort * 90.0 /
params->undistort_fov; // slightly lower than 0.5 cols when fov=200
for (int i = 0; i < pts.size(); i++) {
for (unsigned int i = 0; i < pts.size(); i++) {
if (require_left && pts[i].x < params->width_undistort - move_cols ||
!require_left && pts[i].x >= move_cols) {
tmp_to_idx[c] = i;
Expand Down Expand Up @@ -1183,7 +1183,7 @@ bool D2FeatureTracker::matchLocalFeatures(
params->width_undistort * 90.0 /
params
->undistort_fov; // slightly lower than 0.5 cols when fov=200
for (int i = 0; i < features_a.second.size(); i++) {
for (unsigned int i = 0; i < features_a.second.size(); i++) {
features_a.second[i].x +=
param.type == LEFT_RIGHT_IMG_MATCH ? move_cols : -move_cols;
}
Expand Down Expand Up @@ -1261,10 +1261,10 @@ bool D2FeatureTracker::matchLocalFeatures(
char name[100];
std::vector<cv::KeyPoint> kps_a, kps_b;
// Kps from points
for (int i = 0; i < pts_a.size(); i++) {
for (unsigned int i = 0; i < pts_a.size(); i++) {
kps_a.push_back(cv::KeyPoint(pts_a[i].x, pts_a[i].y, 1));
}
for (int i = 0; i < pts_b.size(); i++) {
for (unsigned int i = 0; i < pts_b.size(); i++) {
kps_b.push_back(cv::KeyPoint(pts_b[i].x, pts_b[i].y, 1));
}
cv::Mat show;
Expand All @@ -1283,7 +1283,7 @@ bool D2FeatureTracker::matchLocalFeatures(
cv::Mat show_check;
cv::hconcat(img_desc_a.raw_image, image_b, show_check);
cv::cvtColor(show_check, show_check, cv::COLOR_GRAY2BGR);
for (int i = 0; i < matched_pts_a.size(); i++) {
for (unsigned int i = 0; i < matched_pts_a.size(); i++) {
// random color
cv::Scalar color(rand() & 255, rand() & 255, rand() & 255);
cv::line(show_check, matched_pts_a[i],
Expand Down Expand Up @@ -1320,7 +1320,7 @@ D2FeatureTracker::predictLandmarksWithExtrinsic(
const Swarm::Pose &cam_pose_b) const {
std::map<LandmarkIdType, cv::Point2f> pts_a_pred_on_b;
auto cam = cams.at(camera_index);
for (int i = 0; i < pts_3d_norm.size(); i++) {
for (unsigned int i = 0; i < pts_3d_norm.size(); i++) {
Vector3d landmark_pos_cam =
pts_3d_norm[i] * _config.landmark_distance_assumption;
Vector3d pt3d = cam_pose_a * landmark_pos_cam;
Expand All @@ -1338,7 +1338,7 @@ std::vector<cv::Point2f> D2FeatureTracker::predictLandmarks(
std::vector<cv::Point2f> pts_a_pred_on_b;
assert(img_desc_a.drone_id == params->self_id);
auto cam = cams.at(img_desc_a.camera_index);
for (int i = 0; i < img_desc_a.spLandmarkNum(); i++) {
for (unsigned int i = 0; i < img_desc_a.spLandmarkNum(); i++) {
auto landmark_id = img_desc_a.landmarks[i].landmark_id;
// Query 3d landmark position
bool find_position = false;
Expand Down
2 changes: 1 addition & 1 deletion d2frontend/src/loop_cam.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -117,7 +117,7 @@ double triangulatePoint(Eigen::Quaterniond q0, Eigen::Vector3d t0,
template <typename T>
void reduceVector(std::vector<T> &v, std::vector<uchar> status) {
int j = 0;
for (int i = 0; i < int(v.size()); i++)
for (unsigned int i = 0; i < v.size(); i++)
if (status[i]) v[j++] = v[i];
v.resize(j);
}
Expand Down
2 changes: 1 addition & 1 deletion d2frontend/src/loop_detector.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -747,7 +747,7 @@ void LoopDetector::drawMatched(
}
std::set<int> inlier_set(inliers.begin(), inliers.end());

for (int i = 0; i < index2dirindex_a.size(); i++) {
for (unsigned int i = 0; i < index2dirindex_a.size(); i++) {
int old_pt_id = index2dirindex_b[i].second;
int old_dir_id = index2dirindex_b[i].first;

Expand Down
14 changes: 7 additions & 7 deletions d2frontend/src/loop_utils.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -362,7 +362,7 @@ std::vector<cv::Point2f> opticalflowTrack(const cv::Mat &cur_img,
status[i] = 0;
}

for (int i = 0; i < int(cur_pts.size()); i++) {
for (unsigned int i = 0; i < cur_pts.size(); i++) {
if (status[i] && !inBorder(cur_pts[i], cur_img.size())) {
status[i] = 0;
}
Expand Down Expand Up @@ -468,7 +468,7 @@ LKImageInfoGPU opticalflowTrackPyr(const cv::Mat &cur_img,
status[i] = 0;
}

for (int i = 0; i < int(cur_pts.size()); i++) {
for (unsigned int i = 0; i < cur_pts.size(); i++) {
if (status[i] && !inBorder(cur_pts[i], cur_img.size())) {
status[i] = 0;
}
Expand Down Expand Up @@ -580,7 +580,7 @@ std::vector<cv::Point2f> detectFastByRegion(cv::InputArray _img,
return a.response > b.response;
});
// Return the top features
for (int i = 0; i < total_kpts.size(); i++) {
for (unsigned int i = 0; i < total_kpts.size(); i++) {
ret.push_back(total_kpts[i].pt);
if (ret.size() >= features) {
break;
Expand Down Expand Up @@ -632,7 +632,7 @@ int computeRelativePosePnP(const std::vector<Vector3d> lm_positions_a,
int iteratives = 100;
Point3fVector pts3d;
Point2fVector pts2d;
for (int i = 0; i < lm_positions_a.size(); i++) {
for (unsigned int i = 0; i < lm_positions_a.size(); i++) {
auto z = lm_3d_norm_b[i].z();
if (z > 1e-1) {
pts3d.push_back(cv::Point3f(lm_positions_a[i].x(), lm_positions_a[i].y(),
Expand Down Expand Up @@ -676,12 +676,12 @@ Swarm::Pose computePosePnPnonCentral(
opengv::points_t points;
opengv::rotations_t camRotations;
opengv::translations_t camOffsets;
for (int i = 0; i < lm_positions_a.size(); i++) {
for (unsigned int i = 0; i < lm_positions_a.size(); i++) {
bearings.push_back(lm_3d_norm_b[i]);
camCorrespondences.push_back(camera_indices[i]);
points.push_back(lm_positions_a[i]);
}
for (int i = 0; i < cam_extrinsics.size(); i++) {
for (unsigned int i = 0; i < cam_extrinsics.size(); i++) {
camRotations.push_back(cam_extrinsics[i].R());
camOffsets.push_back(cam_extrinsics[i].pos());
}
Expand Down Expand Up @@ -714,7 +714,7 @@ Swarm::Pose computePosePnPnonCentral(
bearings.clear();
camCorrespondences.clear();
points.clear();
for (int i = 0; i < lm_positions_a.size(); i++) {
for (unsigned int i = 0; i < lm_positions_a.size(); i++) {
if (inlier_set.find(i) == inlier_set.end()) {
continue;
}
Expand Down
2 changes: 1 addition & 1 deletion d2pgo/src/d2pgo.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -470,7 +470,7 @@ void D2PGO::setupLoopFactors(SolverWrapper* solver,
void D2PGO::setupEgoMotionFactors(SolverWrapper* solver, int drone_id) {
auto frames = state.getFrames(drone_id);
auto traj = state.getEgomotionTraj(drone_id);
for (int i = 0; i < frames.size() - 1; i++) {
for (unsigned int i = 0; i < frames.size() - 1; i++) {
auto frame_a = frames[i];
auto frame_b = frames[i + 1];
Swarm::Pose rel_pose;
Expand Down
2 changes: 1 addition & 1 deletion d2pgo/src/rot_init/rotation_initialization_base.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,7 @@ using D2Common::Utility::TicToc;

template <typename Derived, typename T>
inline void fillInTripet(int i0, int j0, const MatrixBase<Derived> & M, std::vector<Eigen::Triplet<T>> & triplets) {
for (int i = 0; i < M.rows(); i ++) { //Row, col of relative rotation R
for (unsigned int i = 0; i < M.rows(); i ++) { //Row, col of relative rotation R
for (int j = 0; j < M.cols(); j ++) {
triplets.emplace_back(Eigen::Triplet<T>(i0 + i, j0 + j, M(i, j)));
}
Expand Down
Loading

0 comments on commit ece2a40

Please sign in to comment.