Skip to content

Commit

Permalink
Use c++11 initilizer list {a, b} to replace std::make_pair.
Browse files Browse the repository at this point in the history
Less verbose
  • Loading branch information
pmoulon committed Jul 6, 2017
1 parent c843fe1 commit bf71e64
Show file tree
Hide file tree
Showing 26 changed files with 78 additions and 89 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -99,10 +99,8 @@ static void Encode_histo_relation(
vec_sign.resize(Nconstraint);

// By default set free variable:
vec_bounds = std::vector< std::pair<double,double> >(NVar);
std::fill( vec_bounds.begin(), vec_bounds.end(),
std::make_pair(std::numeric_limits<double>::lowest(),
std::numeric_limits<double>::max()));
vec_bounds.assign(NVar,
{std::numeric_limits<double>::lowest(), std::numeric_limits<double>::max()});

// Set gain as positive values
for (size_t i = 0; i < Nima; ++i)
Expand Down
4 changes: 2 additions & 2 deletions src/openMVG/features/liop/liop_descriptor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -404,7 +404,7 @@ void Liop_Descriptor_Extractor::GeneratePatternMap(
p[i] = i + 1;
key += p[i]*pos_weight[n-i-1];
}
pattern_map.insert(std::make_pair(key,count));
pattern_map.insert({key,count});
++count;

while(NextPermutation(p, n))
Expand All @@ -414,7 +414,7 @@ void Liop_Descriptor_Extractor::GeneratePatternMap(
{
key += p[i]*pos_weight[n-i-1];
}
pattern_map.insert(std::make_pair(key, count));
pattern_map.insert({key, count});
++count;
}
}
Expand Down
7 changes: 3 additions & 4 deletions src/openMVG/geometry/half_space_intersection.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -39,10 +39,9 @@ bool isNotEmpty
LP_Constraints cstraint;
{
cstraint.nbParams_ = 3; // {X,Y,Z}
cstraint.vec_bounds_.resize( cstraint.nbParams_ );
std::fill( cstraint.vec_bounds_.begin(), cstraint.vec_bounds_.end(),
std::make_pair( std::numeric_limits<double>::lowest(),
std::numeric_limits<double>::max() )); // [X,Y,Z] => -inf, +inf
cstraint.vec_bounds_.assign( cstraint.nbParams_,
{std::numeric_limits<double>::lowest(),
std::numeric_limits<double>::max()}); // [X,Y,Z] => -inf, +inf
cstraint.bminimize_ = true;

// Configure constraints
Expand Down
2 changes: 1 addition & 1 deletion src/openMVG/graph/connectedComponent.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -194,7 +194,7 @@ std::set<IndexT> KeepLargestCC_Nodes
for (const unsigned int parent_id_it : parent_id)
{
if (uf.m_cc_size[parent_id_it] > max_cc.second) // Update the component parent id and size
max_cc = std::make_pair(parent_id_it, uf.m_cc_size[parent_id_it]);
max_cc = {parent_id_it, uf.m_cc_size[parent_id_it]};
}
}
if (max_cc.first != UndefinedIndexT)
Expand Down
4 changes: 2 additions & 2 deletions src/openMVG/graph/triplet_finder.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -71,8 +71,8 @@ struct Triplet
*/
friend bool operator==( const Triplet& m1, const Triplet& m2 )
{
return m1.contain( std::make_pair( m2.i, m2.j ) )
&& m1.contain( std::make_pair( m2.i, m2.k ) );
return m1.contain( {m2.i, m2.j} )
&& m1.contain( {m2.i, m2.k} );
}

/**
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -72,10 +72,8 @@ void EncodeTi_from_tij
vec_sign.resize(Nconstraint);

// By default set free variables:
vec_bounds = std::vector< std::pair<double,double> >(NVar);
std::fill( vec_bounds.begin(), vec_bounds.end(),
std::make_pair(std::numeric_limits<double>::lowest(),
std::numeric_limits<double>::max()));
vec_bounds.assign(NVar,
{std::numeric_limits<double>::lowest(), std::numeric_limits<double>::max()});
// Make first camera at origin (translation ambiguity)
vec_bounds[TVAR(0,0)].first = vec_bounds[TVAR(0,0)].second = 0;
vec_bounds[TVAR(0,1)].first = vec_bounds[TVAR(0,1)].second = 0;
Expand Down
4 changes: 2 additions & 2 deletions src/openMVG/linearProgramming/lInfinityCV/resection.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -167,8 +167,8 @@ bool Resection_L1_ConstraintBuilder::Build
const int NParams = 4 * 2 + 3;

constraint.nbParams_ = NParams;
constraint.vec_bounds_ = { std::make_pair(std::numeric_limits<double>::lowest(),
std::numeric_limits<double>::max()) };
constraint.vec_bounds_ = { {std::numeric_limits<double>::lowest(),
std::numeric_limits<double>::max()} };
// Constraint sign are all LESS or equal (<=)
constraint.vec_sign_.resize(constraint.constraint_mat_.rows());
std::fill(constraint.vec_sign_.begin(), constraint.vec_sign_.end(),
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -82,7 +82,7 @@ TEST(Resection_L_Infinity, Robust_OneOutlier) {
d2._t[nResectionCameraIndex].fill(0.0);

// Set 20% of the 3D point as outlier
const int nbOutlier = nbPoints*0.2;
const int nbOutlier = nbPoints * 0.2;
for (int i=0; i < nbOutlier; ++i)
{
d2._X.col(i)(0) += 120.0;
Expand Down Expand Up @@ -114,7 +114,12 @@ TEST(Resection_L_Infinity, Robust_OneOutlier) {

//Check matrix to GT, and residual
EXPECT_NEAR( 0.0, FrobeniusDistance(GT_ProjectionMatrix, COMPUTED_ProjectionMatrix), 1e-3 );
EXPECT_NEAR( 0.0, RootMeanSquareError(pt2D, pt3D.colwise().homogeneous(), COMPUTED_ProjectionMatrix), 1e-1);
// Check that all the inlier have a very small residual reprojection error
EXPECT_NEAR( 0.0, RootMeanSquareError(
pt2D.rightCols(nbPoints - nbOutlier) ,
pt3D.colwise().homogeneous().rightCols(nbPoints - nbOutlier),
COMPUTED_ProjectionMatrix),
1e-1);
}
d2.ExportToPLY("test_After_Infinity.ply");
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -66,12 +66,10 @@ void EncodeTiXi
# define XVAR(j, el) (pointStart + 3*(j) + (el))

// By default set free variable:
vec_bounds = std::vector< std::pair<double,double> >(3 * (N3D + Ncam));
std::fill( vec_bounds.begin(), vec_bounds.end(),
std::make_pair(std::numeric_limits<double>::lowest(),
std::numeric_limits<double>::max()));
vec_bounds.assign(3 * (N3D + Ncam),
{std::numeric_limits<double>::lowest(), std::numeric_limits<double>::max()});
// Fix the translation ambiguity. (set first cam at (0,0,0))
vec_bounds[0] = vec_bounds[1] = vec_bounds[2] = std::make_pair(0,0);
vec_bounds[0] = vec_bounds[1] = vec_bounds[2] = {0,0};

size_t rowPos = 0;
// Add the cheirality conditions (R_i*X_j + T_i)_3 >= 1
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -88,10 +88,8 @@ void EncodeTiXi_withNoise
}

// By default set free variable:
vec_bounds = std::vector< std::pair<double,double> >(3 * (Ncam + N3D + Nobs));
std::fill( vec_bounds.begin(), vec_bounds.end(),
std::make_pair(std::numeric_limits<double>::lowest(),
std::numeric_limits<double>::max()));
vec_bounds.assign( 3 * (Ncam + N3D + Nobs),
{std::numeric_limits<double>::lowest(), std::numeric_limits<double>::max()});
// Change the offset to be positive
for (size_t k = 0; k < 3*Nobs; ++k)
vec_bounds[offsetStart + k].first = 0;
Expand Down
4 changes: 2 additions & 2 deletions src/openMVG/linearProgramming/lInfinityCV/triangulation.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -110,8 +110,8 @@ struct Triangulation_L1_ConstraintBuilder
// We look for 3 variables [X,Y,Z] with no bounds.
// Constraint sign are all less or equal (<=)
constraint.nbParams_ = 3;
constraint.vec_bounds_ = {std::make_pair(std::numeric_limits<double>::lowest(),
std::numeric_limits<double>::max())};
constraint.vec_bounds_ = {{std::numeric_limits<double>::lowest(),
std::numeric_limits<double>::max()}};
// Setup constraint sign
constraint.vec_sign_.resize(constraint.constraint_mat_.rows());
fill(constraint.vec_sign_.begin(), constraint.vec_sign_.end(),
Expand Down
10 changes: 3 additions & 7 deletions src/openMVG/linearProgramming/linearProgramming_test.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -52,10 +52,8 @@ void BuildLinearProblem(LP_Constraints & cstraint)
std::fill_n(cstraint.vec_sign_.begin(), 3, LP_Constraints::LP_LESS_OR_EQUAL);
std::fill_n(cstraint.vec_sign_.begin()+3, 2, LP_Constraints::LP_GREATER_OR_EQUAL);

cstraint.vec_bounds_ = std::vector< std::pair<double,double> >(cstraint.nbParams_);
std::fill(cstraint.vec_bounds_.begin(),cstraint.vec_bounds_.end(),
std::make_pair(std::numeric_limits<double>::lowest(),
std::numeric_limits<double>::max()));
cstraint.vec_bounds_.assign(cstraint.nbParams_,
{std::numeric_limits<double>::lowest(), std::numeric_limits<double>::max()});
}

TEST(linearProgramming, osiclp_dense_sample) {
Expand Down Expand Up @@ -120,9 +118,7 @@ void BuildSparseLinearProblem(LP_Constraints_Sparse & cstraint)
vec_sign[2] = LP_Constraints::LP_LESS_OR_EQUAL;

// Variable bounds
cstraint.vec_bounds_ = std::vector< std::pair<double,double> >(4);
std::fill(cstraint.vec_bounds_.begin(),cstraint.vec_bounds_.end(),
std::make_pair(0.0, std::numeric_limits<double>::max()));
cstraint.vec_bounds_.assign(4, {0.0, std::numeric_limits<double>::max()});
cstraint.vec_bounds_[1].second = 10;

// Objective to maximize
Expand Down
2 changes: 1 addition & 1 deletion src/openMVG/matching/pairwiseAdjacencyDisplay.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,7 @@ void PairWiseMatchingToAdjacencyMatrixSVG
for (size_t I = 0; I < NbImages; ++I) {
for (size_t J = 0; J < NbImages; ++J) {
// If the pair have matches display a blue boxes at I,J position.
auto iterSearch = map_Matches.find(std::make_pair(I,J));
auto iterSearch = map_Matches.find({I,J});
if (iterSearch != map_Matches.end() && !iterSearch->second.empty())
{
// Display as a tooltip: (IndexI, IndexJ NbMatches)
Expand Down
3 changes: 1 addition & 2 deletions src/openMVG/matching_image_collection/GeometricFilter.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -120,8 +120,7 @@ void ImageCollectionGeometricFilter::Robust_model_estimation
#pragma omp critical
#endif
{
_map_GeometricMatches.insert(
std::make_pair(current_pair, std::move(putative_inliers)));
_map_GeometricMatches.insert( {current_pair, std::move(putative_inliers)});
}
}
}
Expand Down
10 changes: 4 additions & 6 deletions src/openMVG/multiview/projection.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -254,9 +254,9 @@ void HomogeneousToNormalizedCamera(const Mat3X &x, const Mat3 &K, Mat2X *n) {
double RootMeanSquareError(const Mat2X &x_image,
const Mat4X &X_world,
const Mat34 &P) {
size_t num_points = x_image.cols();
Mat2X dx = Project(P, X_world) - x_image;
return dx.norm() / num_points;
const Mat2X::Index num_points = x_image.cols();
const Mat2X dx = Project(P, X_world) - x_image;
return std::sqrt(dx.squaredNorm() / num_points);
}

/// Estimates the root mean square error (2D)
Expand All @@ -267,9 +267,7 @@ double RootMeanSquareError(const Mat2X &x_image,
const Vec3 &t) {
Mat34 P;
P_From_KRt(K, R, t, &P);
size_t num_points = x_image.cols();
Mat2X dx = Project(P, X_world) - x_image;
return dx.norm() / num_points;
return RootMeanSquareError(x_image, X_world.colwise().homogeneous(), P);
}

} // namespace openMVG
2 changes: 1 addition & 1 deletion src/openMVG/multiview/rotation_averaging_common.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -43,7 +43,7 @@ inline Pair_Set getPairs(const RelativeRotations & relRots)
{
Pair_Set pairs;
for (const auto & cur_rotation : relRots )
pairs.insert(std::make_pair(cur_rotation.i, cur_rotation.j));
pairs.insert({cur_rotation.i, cur_rotation.j});
return pairs;
}

Expand Down
12 changes: 6 additions & 6 deletions src/openMVG/multiview/rotation_averaging_l1.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -63,7 +63,7 @@ ComputeX84Threshold(const TYPE* const values, uint32_t size, TYPE mul=TYPE(5.2))
for (size_t i=0; i<size; ++i)
data[i] = std::abs(values[i]-median);
std::nth_element(data.begin(), mid, data.end());
return std::make_pair(median, mul*(*mid));
return {median, mul*(*mid)};
} // ComputeX84Threshold


Expand Down Expand Up @@ -108,8 +108,8 @@ uint32_t FindMaximumSpanningTree(const RelativeRotations& RelRs, graph_t& g, Map
for (size_t p = 0; p < RelRs.size(); ++p) {
const RelativeRotation& relR = RelRs[p];
boost::add_edge(relR.i, relR.j, - relR.weight, g);
mapIJ2R[std::make_pair(relR.i, relR.j)] = relR.Rij;
mapIJ2R[std::make_pair(relR.j, relR.i)] = relR.Rij.transpose();
mapIJ2R[{relR.i, relR.j}] = relR.Rij;
mapIJ2R[{relR.j, relR.i}] = relR.Rij.transpose();
}
// find the minimum spanning tree
const size_t nViews = boost::num_vertices(g);
Expand Down Expand Up @@ -145,8 +145,8 @@ uint32_t FindMaximumSpanningTree(const RelativeRotations& RelRs, graph_t& g, Map
map_EdgeMap map_edgeMap(g);
for (size_t p = 0; p < RelRs.size(); ++p) {
const RelativeRotation& relR = RelRs[p];
mapIJ2R[std::make_pair(relR.i, relR.j)] = relR.Rij;
mapIJ2R[std::make_pair(relR.j, relR.i)] = relR.Rij.transpose();
mapIJ2R[{relR.i, relR.j}] = relR.Rij;
mapIJ2R[{relR.j, relR.i}] = relR.Rij.transpose();

// add edge to the graph
graph_t::Edge edge = g.addEdge(map_index_to_node[relR.i], map_index_to_node[relR.j]);
Expand Down Expand Up @@ -290,7 +290,7 @@ void InitRotationsMST
if (edge == link.parentID) {
// compute the global rotation for the current node
assert(mapIJ2R.find(std::make_pair(link.parentID, link.ID)) != mapIJ2R.end());
const Matrix3x3& Rij = mapIJ2R[std::make_pair(link.parentID, link.ID)];
const Matrix3x3& Rij = mapIJ2R[{link.parentID, link.ID}];
Rs[link.ID] = Rij * Rs[link.parentID];
} else {
// add edge to the processing queue
Expand Down
2 changes: 1 addition & 1 deletion src/openMVG/multiview/rotation_averaging_l2.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -155,7 +155,7 @@ bool L2RotationAveraging
std::vector<std::pair<double, Vec> > eigs(AtA.cols());
for (Mat::Index i = 0; i < AtA.cols(); ++i)
{
eigs[i] = std::make_pair(es.eigenvalues()[i], es.eigenvectors().col(i));
eigs[i] = {es.eigenvalues()[i], es.eigenvectors().col(i)};
}
std::stable_sort(eigs.begin(), eigs.end(), &compare_first_abs);

Expand Down
4 changes: 2 additions & 2 deletions src/openMVG/multiview/translation_averaging_common.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -20,10 +20,10 @@
namespace openMVG {

/// Relative information [Rij|tij] for a pair
using relativeInfo = std::pair< Pair, std::pair<Mat3,Vec3> >;
using relativeInfo = std::pair< Pair, std::pair<Mat3,Vec3>>;

using RelativeInfo_Vec = std::vector< relativeInfo >;
using RelativeInfo_Map = std::map< Pair, std::pair<Mat3, Vec3> >;
using RelativeInfo_Map = std::map< Pair, std::pair<Mat3, Vec3>>;

// List the pairs used by the relative motions
Pair_Set getPairs(const RelativeInfo_Vec & vec_relative);
Expand Down
4 changes: 2 additions & 2 deletions src/openMVG/robust_estimation/robust_estimator_ACRansac.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -337,7 +337,7 @@ std::pair<double, double> ACRANSAC
const unsigned int sizeSample = Kernel::MINIMUM_SAMPLES;
const unsigned int nData = kernel.NumSamples();
if (nData <= sizeSample)
return std::make_pair(0.0,0.0);
return {0.0, 0.0};

//--
// Sampling:
Expand Down Expand Up @@ -483,7 +483,7 @@ std::pair<double, double> ACRANSAC
errorMax = kernel.unormalizeError(errorMax);
}

return std::make_pair(errorMax, minNFA);
return {errorMax, minNFA};
}

} // namespace robust
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -372,9 +372,9 @@ void GlobalSfM_Translation_AveragingSolver::ComputePutativeTranslation_EdgesCove
for (size_t i = 0; i < vec_triplets.size(); ++i)
{
const graph::Triplet & triplet = vec_triplets[i];
map_tripletIds_perEdge[std::make_pair(triplet.i, triplet.j)].push_back(i);
map_tripletIds_perEdge[std::make_pair(triplet.i, triplet.k)].push_back(i);
map_tripletIds_perEdge[std::make_pair(triplet.j, triplet.k)].push_back(i);
map_tripletIds_perEdge[{triplet.i, triplet.j}].push_back(i);
map_tripletIds_perEdge[{triplet.i, triplet.k}].push_back(i);
map_tripletIds_perEdge[{triplet.j, triplet.k}].push_back(i);
}

//-- precompute the visibility count per triplets (sum of their 2 view matches)
Expand Down Expand Up @@ -490,9 +490,9 @@ void GlobalSfM_Translation_AveragingSolver::ComputePutativeTranslation_EdgesCove
#pragma omp critical
#endif
{
m_mutexSet.insert(std::make_pair(triplet.i, triplet.j));
m_mutexSet.insert(std::make_pair(triplet.j, triplet.k));
m_mutexSet.insert(std::make_pair(triplet.i, triplet.k));
m_mutexSet.insert({triplet.i, triplet.j});
m_mutexSet.insert({triplet.j, triplet.k});
m_mutexSet.insert({triplet.i, triplet.k});
}

// Compute the triplet relative motions (IJ, JK, IK)
Expand Down Expand Up @@ -525,12 +525,12 @@ void GlobalSfM_Translation_AveragingSolver::ComputePutativeTranslation_EdgesCove
#endif

RelativeInfo_Vec triplet_relative_motion;
triplet_relative_motion.emplace_back(
std::make_pair(triplet.i, triplet.j), std::make_pair(Rij, tij));
triplet_relative_motion.emplace_back(
std::make_pair(triplet.j, triplet.k), std::make_pair(Rjk, tjk));
triplet_relative_motion.emplace_back(
std::make_pair(triplet.i, triplet.k), std::make_pair(Rik, tik));
triplet_relative_motion.push_back(
{{triplet.i, triplet.j}, {Rij, tij}});
triplet_relative_motion.push_back(
{{triplet.j, triplet.k}, {Rjk, tjk}});
triplet_relative_motion.push_back(
{{triplet.i, triplet.k}, {Rik, tik}});

initial_estimates[thread_id].emplace_back(triplet_relative_motion);

Expand Down
2 changes: 1 addition & 1 deletion src/openMVG/sfm/pipelines/localization/SfM_Localizer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -142,7 +142,7 @@ namespace sfm {
// Setup a tiny SfM scene with the corresponding 2D-3D data
SfM_Data sfm_data;
// view
sfm_data.views.insert(std::make_pair(0, std::make_shared<View>("",0, 0, 0)));
sfm_data.views.insert({0, std::make_shared<View>("",0, 0, 0)});
// pose
sfm_data.poses[0] = pose;
// intrinsic
Expand Down
8 changes: 4 additions & 4 deletions src/openMVG/sfm/pipelines/sequential/sequential_SfM.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -424,7 +424,7 @@ bool SequentialSfMReconstructionEngine::AutomaticInitialPairChoice(Pair & initia
if (robustRelativePose(
cam_I->K(), cam_J->K(),
xI, xJ, relativePose_info,
std::make_pair(cam_I->w(), cam_I->h()), std::make_pair(cam_J->w(), cam_J->h()),
{cam_I->w(), cam_I->h()}, {cam_J->w(), cam_J->h()},
256) && relativePose_info.vec_inliers.size() > iMin_inliers_count)
{
// Triangulate inliers & compute angle between bearing vectors
Expand Down Expand Up @@ -610,8 +610,8 @@ bool SequentialSfMReconstructionEngine::MakeInitialPair3D(const Pair & current_p
// Save computed data
const Pose3 pose_I = sfm_data_.poses[view_I->id_pose] = tiny_scene.poses[view_I->id_pose];
const Pose3 pose_J = sfm_data_.poses[view_J->id_pose] = tiny_scene.poses[view_J->id_pose];
map_ACThreshold_.insert(std::make_pair(I, relativePose_info.found_residual_precision));
map_ACThreshold_.insert(std::make_pair(J, relativePose_info.found_residual_precision));
map_ACThreshold_.insert({I, relativePose_info.found_residual_precision});
map_ACThreshold_.insert({J, relativePose_info.found_residual_precision});
set_remaining_view_id_.erase(view_I->id_view);
set_remaining_view_id_.erase(view_J->id_view);

Expand Down Expand Up @@ -1038,7 +1038,7 @@ bool SequentialSfMReconstructionEngine::Resection(const uint32_t viewIndex)
// - the new found camera pose
sfm_data_.poses[view_I->id_pose] = pose;
// - track the view's AContrario robust estimation found threshold
map_ACThreshold_.insert(std::make_pair(viewIndex, resection_data.error_max));
map_ACThreshold_.insert({viewIndex, resection_data.error_max});
// - intrinsic parameters (if the view has no intrinsic group add a new one)
if (b_new_intrinsic)
{
Expand Down
Loading

0 comments on commit bf71e64

Please sign in to comment.