Skip to content

Commit

Permalink
[build] sanitize
Browse files Browse the repository at this point in the history
  • Loading branch information
pmoulon committed Aug 31, 2016
1 parent 529ebcc commit da7d51d
Show file tree
Hide file tree
Showing 33 changed files with 232 additions and 227 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -217,7 +217,7 @@ struct ConstraintBuilder_GainOffset
{
//Count the number of images
std::set<size_t> countSet;
for (int i = 0; i < _vec_relative.size(); ++i)
for (size_t i = 0; i < _vec_relative.size(); ++i)
{
countSet.insert(_vec_relative[i].I);
countSet.insert(_vec_relative[i].J);
Expand Down
6 changes: 3 additions & 3 deletions src/openMVG/color_harmonization/selection_VLDSegment.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -24,11 +24,11 @@ class commonDataByPair_VLDSegment : public commonDataByPair
const vector< features::SIOPointFeature >& vec_featsL,
const vector< features::SIOPointFeature >& vec_featsR):
commonDataByPair( sLeftImage, sRightImage ),
_vec_PutativeMatches( vec_PutativeMatches ),
_vec_featsL( vec_featsL ), _vec_featsR( vec_featsR )
_vec_featsL( vec_featsL ), _vec_featsR( vec_featsR ),
_vec_PutativeMatches( vec_PutativeMatches )
{}

~commonDataByPair_VLDSegment() override = default ;
~commonDataByPair_VLDSegment() override = default ;

/**
* Put masks to white, images are conserved
Expand Down
7 changes: 4 additions & 3 deletions src/openMVG/color_harmonization/selection_matchedPoints.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -27,11 +27,12 @@ class commonDataByPair_MatchedPoints : public commonDataByPair
const std::vector< features::SIOPointFeature >& vec_featsR,
const size_t radius = 1 ):
commonDataByPair( sLeftImage, sRightImage ),
_radius( radius ),
_vec_PutativeMatches( vec_PutativeMatches ),
_vec_featsL( vec_featsL ), _vec_featsR( vec_featsR ), _radius( radius )
_vec_featsL( vec_featsL ), _vec_featsR( vec_featsR )
{}

~commonDataByPair_MatchedPoints() override = default ;
~commonDataByPair_MatchedPoints() override = default ;

/**
* Fill mask from corresponding points (each point pictured by a disk of radius _radius)
Expand All @@ -41,7 +42,7 @@ class commonDataByPair_MatchedPoints : public commonDataByPair
*
* \return True if some pixel have been set to true.
*/
bool computeMask( image::Image< unsigned char > & maskLeft, image::Image< unsigned char > & maskRight ) override
bool computeMask( image::Image< unsigned char > & maskLeft, image::Image< unsigned char > & maskRight ) override
{
maskLeft.fill(0);
maskRight.fill(0);
Expand Down
12 changes: 6 additions & 6 deletions src/openMVG/geometry/rigid_transformation3D_srt.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -226,12 +226,12 @@ static void Refine_RTS( const Mat &x1,

lm.minimize( xlm );

Vec3 transAdd = xlm.block<3, 1>( 0, 0 );
Vec3 rot = xlm.block<3, 1>( 3, 0 );
double SAdd = xlm( 6 );
const Vec3 transAdd = xlm.block<3, 1>( 0, 0 );
const Vec3 rot = xlm.block<3, 1>( 3, 0 );
const double SAdd = xlm( 6 );

//Build the rotation matrix
Mat3 Rcor =
const Mat3 Rcor =
( Eigen::AngleAxis<double>( rot( 0 ), Vec3::UnitX() )
* Eigen::AngleAxis<double>( rot( 1 ), Vec3::UnitY() )
* Eigen::AngleAxis<double>( rot( 2 ), Vec3::UnitZ() ) ).toRotationMatrix();
Expand All @@ -253,10 +253,10 @@ static void Refine_RTS( const Mat &x1,

lm.minimize( xlm );

Vec3 rot = xlm.block<3, 1>( 0, 0 );
const Vec3 rot = xlm.block<3, 1>( 0, 0 );

//Build the rotation matrix
Mat3 Rcor =
const Mat3 Rcor =
( Eigen::AngleAxis<double>( rot( 0 ), Vec3::UnitX() )
* Eigen::AngleAxis<double>( rot( 1 ), Vec3::UnitY() )
* Eigen::AngleAxis<double>( rot( 2 ), Vec3::UnitZ() ) ).toRotationMatrix();
Expand Down
15 changes: 0 additions & 15 deletions src/openMVG/image/image_container.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -9,21 +9,6 @@

#include "openMVG/numeric/numeric.h"

//---------------------------------
// Universal Image Processing Algorithm
// _ _ __ ___ __
// ( )( )( )( ,\( )
// ( )( ) )( ) _//__\
// (____)(__)(_) (_)(_)
//-------
//-- Container for a 2D image
//-- This class ensure that the image have a width and a height
//-- and a 2D array of T data.
//-
//-- Data is saved in row major format
//-- Pixel access is done with operator(y,x)
// [2/3/2011 pierre MOULON]
//---------------------------
namespace openMVG
{
namespace image
Expand Down
16 changes: 0 additions & 16 deletions src/openMVG/image/image_drawing.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -4,22 +4,6 @@
// License, v. 2.0. If a copy of the MPL was not distributed with this
// file, You can obtain one at http://mozilla.org/MPL/2.0/.


//---------------------------------
// Universal Image Processing Algorithm (UIPA)
// _ _ __ ___ __
// ( )( )( )( ,\( )
// ( )( ) )( ) _//__\
// (____)(__)(_) (_)(_)
//-------
// Generic Image algorithm that require
// an ImageModel class that must implement the following:
//
// ::Contains(int y, int x) <= Tell if a point is inside or not the image
// ::operator(int y,int x) <= Modification accessor over the pixel (y,x)
// ::Width()
// ::Height()

#ifndef OPENMVG_IMAGE_IMAGE_DRAWING_HPP
#define OPENMVG_IMAGE_IMAGE_DRAWING_HPP

Expand Down
2 changes: 1 addition & 1 deletion src/openMVG/matching/kvld/algorithm.h
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,7 @@ struct PointS
PointS( float x = (0.f), float y = (0.f)):
x( x ), y( y ), scale(0.f), angle(0.f){}
PointS( const float& x, const float& y,const float& angle,const float& scale):
x( x ), y( y ), angle( angle ), scale( scale ){}
x( x ), y( y ), scale( scale ), angle( angle ){}
};

//===================================== integral image ====================================//
Expand Down
32 changes: 16 additions & 16 deletions src/openMVG/matching/kvld/kvld.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -232,12 +232,12 @@ float KVLD( const Image< float >& I1,
dist1 = openMVG::Matf::Zero( F1.size(), F1.size() );
dist2 = openMVG::Matf::Zero( F2.size(), F2.size() );

for( int a1 = 0; a1 < F1.size(); ++a1 )
for( int a2 = a1; a2 < F1.size(); ++a2 )
for( size_t a1 = 0; a1 < F1.size(); ++a1 )
for( size_t a2 = a1; a2 < F1.size(); ++a2 )
dist1( a1, a2 ) = dist1( a2, a1 ) = point_distance( F1[ a1 ], F1[ a2 ] );

for( int b1 = 0; b1 < F2.size(); ++b1 )
for( int b2 = b1; b2 < F2.size(); ++b2 )
for( size_t b1 = 0; b1 < F2.size(); ++b1 )
for( size_t b2 = b1; b2 < F2.size(); ++b2 )
dist2( b1, b2 ) = dist2( b2, b1 ) = point_distance( F2[ b1 ], F2[ b2 ] );
}

Expand All @@ -257,16 +257,16 @@ float KVLD( const Image< float >& I1,
fill( scoretable.begin(), scoretable.end(), 0.0 );
fill( result.begin(), result.end(), 0 );
//========substep 1: search foreach match its neighbors and verify if they are gvld-consistent ============//
for( int it1 = 0; it1 < size - 1; it1++ )
for( size_t it1 = 0; it1 < size - 1; it1++ )
{
if( valide[ it1 ] )
{
size_t a1 = matches[ it1 ].first, b1 = matches[ it1 ].second;

for( int it2 = it1 + 1; it2 < size; it2++ )
for( size_t it2 = it1 + 1; it2 < size; it2++ )
if(valide[ it2 ])
{
size_t a2 = matches[ it2 ].first, b2 = matches[ it2 ].second;
const size_t a2 = matches[ it2 ].first, b2 = matches[ it2 ].second;

bool bOk = false;
if( bPrecomputedDist )
Expand Down Expand Up @@ -312,7 +312,7 @@ float KVLD( const Image< float >& I1,
}

//========substep 2: remove false matches by K gvld-consistency criteria ============//
for( int it = 0; it < size; it++ )
for( size_t it = 0; it < size; it++ )
{
if( valide[ it ] && result[ it ] < kvldParameters.K )
{
Expand All @@ -322,12 +322,12 @@ float KVLD( const Image< float >& I1,
}
//========substep 3: remove multiple matches to a same point by keeping the one with the best average gvld-consistency score ============//
if( uniqueMatch )
for( int it1 = 0; it1 < size - 1; it1++ )
for( size_t it1 = 0; it1 < size - 1; it1++ )
if( valide[ it1 ]) {
size_t a1 = matches[ it1 ].first;
size_t b1 = matches[ it1 ].second;

for( int it2 = it1 + 1; it2 < size; it2++ )
for( size_t it2 = it1 + 1; it2 < size; it2++ )
if( valide[ it2 ] )
{
size_t a2 = matches[ it2 ].first;
Expand Down Expand Up @@ -370,21 +370,21 @@ float KVLD( const Image< float >& I1,
//========substep 4: ifgeometric verification is set, re-score matches by geometric-consistency, and remove poorly scored ones ============================//
if( uniqueMatch && kvldParameters.geometry )
{
for( int i = 0; i < size; i++ )
for( size_t i = 0; i < size; i++ )
scoretable[ i ]=0;

vector< bool > switching;
for( int i = 0; i < size; i++ )
for( size_t i = 0; i < size; i++ )
switching.push_back( false );

for( int it1 = 0; it1 < size; it1++ )
for( size_t it1 = 0; it1 < size; it1++ )
{
if( valide[ it1 ] )
{
size_t a1 = matches[ it1 ].first, b1 = matches[ it1 ].second;
float index = 0.0f;
int good_index = 0;
for( int it2 = 0; it2 < size; it2++ )
for( size_t it2 = 0; it2 < size; it2++ )
{
if( it1 != it2 && valide[ it2 ] )
{
Expand Down Expand Up @@ -416,13 +416,13 @@ float KVLD( const Image< float >& I1,
}
}
}
for( int it1 = 0; it1 < size; it1++ )
for( size_t it1 = 0; it1 < size; it1++ )
if( switching[ it1 ] )
valide[ it1 ] = false;
}
}
//=============== generating output list ===================//
for( int it = 0; it < size; it++ )
for( size_t it = 0; it < size; it++ )
if( valide[ it ] )
{
matchesFiltered.push_back( matches[ it ] );
Expand Down
16 changes: 9 additions & 7 deletions src/openMVG/matching/kvld/kvld.h
Original file line number Diff line number Diff line change
Expand Up @@ -91,14 +91,16 @@ class VLD
template< typename T >
VLD( const ImageScale& series, T const& P1, T const& P2 );
//=========================================class functions==============================================//
inline double get_orientation()const
{
float dy = end_point[ 1 ] - begin_point[ 1 ];
float dx = end_point[ 0 ] - begin_point[ 0 ];
inline double get_orientation()const
{
const float dy = end_point[ 1 ] - begin_point[ 1 ];
const float dx = end_point[ 0 ] - begin_point[ 0 ];
float angle;
anglefrom( dx, dy, angle );
return angle;
}
if (anglefrom( dx, dy, angle ))
return angle;
else
return 0.0;
}
inline double difference( const VLD& vld2 )const
{
double diff[ 2 ];
Expand Down
12 changes: 6 additions & 6 deletions src/openMVG/matching/kvld/kvld_draw.h
Original file line number Diff line number Diff line change
Expand Up @@ -22,23 +22,23 @@ void getKVLDMask(
const std::vector< bool >& vec_valide,
const openMVG::Mat& mat_E)
{
for( int it1 = 0; it1 < vec_matches.size() - 1; it1++ )
for( size_t it1 = 0; it1 < vec_matches.size() - 1; it1++ )
{
for( int it2 = it1 + 1; it2 < vec_matches.size(); it2++ )
for( size_t it2 = it1 + 1; it2 < vec_matches.size(); it2++ )
{
if( vec_valide[ it1 ] && vec_valide[ it2 ] && mat_E( it1, it2 ) >= 0 )
{
const features::SIOPointFeature & l1 = vec_F1[ vec_matches[ it1 ].first ];
const features::SIOPointFeature & l2 = vec_F1[ vec_matches[ it2 ].first ];
float l = ( l1.coords() - l2.coords() ).norm();
int widthL = std::max( 1.f, l / ( dimension + 1.f ) );
const float l = ( l1.coords() - l2.coords() ).norm();
const int widthL = std::max( 1.f, l / ( dimension + 1.f ) );

image::DrawLineThickness(l1.x(), l1.y(), l2.x(), l2.y(), 255, widthL, maskL);

const features::SIOPointFeature & r1 = vec_F2[ vec_matches[ it1 ].second ];
const features::SIOPointFeature & r2 = vec_F2[ vec_matches[ it2 ].second ];
float r = ( r1.coords() - r2.coords() ).norm();
int widthR = std::max( 1.f, r / ( dimension + 1.f ) );
const float r = ( r1.coords() - r2.coords() ).norm();
const int widthR = std::max( 1.f, r / ( dimension + 1.f ) );

image::DrawLineThickness(r1.x(), r1.y(), r2.x(), r2.y(), 255, widthR, maskR);
}
Expand Down
12 changes: 4 additions & 8 deletions src/openMVG/matching/matcher_kdtree_flann.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -126,9 +126,8 @@ class ArrayMatcher_Kdtree_Flann : public ArrayMatcher<Scalar, Metric>
DistanceType * distancePTR = &(vec_distances[0]);
flann::Matrix<DistanceType> dists(distancePTR, nbQuery, NN);

std::vector<int> vec_indices(nbQuery * NN);
int * indicePTR = &(vec_indices[0]);
flann::Matrix<int> indices(indicePTR, nbQuery, NN);
std::vector<int> vec_indices(nbQuery * NN, -1);
flann::Matrix<int> indices(&(vec_indices[0]), nbQuery, NN);

flann::Matrix<Scalar> queries((Scalar*)query, nbQuery, _dimension);
// do a knn search, using 128 checks
Expand All @@ -145,11 +144,8 @@ class ArrayMatcher_Kdtree_Flann : public ArrayMatcher<Scalar, Metric>
{
for (size_t j = 0; j < NN; ++j)
{
if (indices[i] > 0) // rperrot : nullptr here ?
{
pvec_indices->emplace_back(IndMatch(i, vec_indices[i*NN+j]));
pvec_distances->emplace_back(vec_distances[i*NN+j]);
}
pvec_indices->emplace_back(IndMatch(i, vec_indices[i*NN+j]));
pvec_distances->emplace_back(vec_distances[i*NN+j]);
}
}
return true;
Expand Down
10 changes: 5 additions & 5 deletions src/openMVG/matching_image_collection/Geometric_Filter_utils.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -46,14 +46,14 @@ void MatchesPointsToMat
const features::PointFeature & pt_I = feature_I[putativeMatches[i].i_];
const features::PointFeature & pt_J = feature_J[putativeMatches[i].j_];
if (cam_I)
x_I.col(i) = cam_I->get_ud_pixel(pt_I.coords().cast<double>());
x_I.col(i) = cam_I->get_ud_pixel(pt_I.coords().cast<Scalar>());
else
x_I.col(i) = pt_I.coords().cast<double>();
x_I.col(i) = pt_I.coords().cast<Scalar>();

if (cam_J)
x_J.col(i) = cam_J->get_ud_pixel(pt_J.coords().cast<double>());
x_J.col(i) = cam_J->get_ud_pixel(pt_J.coords().cast<Scalar>());
else
x_J.col(i) = pt_J.coords().cast<double>();
x_J.col(i) = pt_J.coords().cast<Scalar>();
}
}

Expand Down Expand Up @@ -140,4 +140,4 @@ void MatchesPairToMat
}

} //namespace matching_image_collection
} // namespace openMVG
} // namespace openMVG
8 changes: 4 additions & 4 deletions src/openMVG/matching_image_collection/Pair_Builder.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@
namespace openMVG {

/// Generate all the (I,J) pairs of the upper diagonal of the NxN matrix
static Pair_Set exhaustivePairs(const size_t N)
inline Pair_Set exhaustivePairs(const size_t N)
{
Pair_Set pairs;
for(size_t I = 0; I < N; ++I)
Expand All @@ -29,7 +29,7 @@ static Pair_Set exhaustivePairs(const size_t N)

/// Generate the pairs that have a distance inferior to the overlapSize
/// Usable to match video sequence
static Pair_Set contiguousWithOverlap(const size_t N, const size_t overlapSize)
inline Pair_Set contiguousWithOverlap(const size_t N, const size_t overlapSize)
{
Pair_Set pairs;
for(size_t I = 0; I < N; ++I)
Expand All @@ -40,7 +40,7 @@ static Pair_Set contiguousWithOverlap(const size_t N, const size_t overlapSize)

/// Load a set of Pair_Set from a file
/// I J K L (pair that link I)
static bool loadPairs(
inline bool loadPairs(
const size_t N, // number of image in the current project (to check index validity)
const std::string &sFileName, // filename of the list file,
Pair_Set & pairs) // output pairs read from the list file
Expand Down Expand Up @@ -95,7 +95,7 @@ static bool loadPairs(
/// I J
/// I K
/// ...
static bool savePairs(const std::string &sFileName, const Pair_Set & pairs)
inline bool savePairs(const std::string &sFileName, const Pair_Set & pairs)
{
std::ofstream outStream(sFileName.c_str());
if(!outStream.is_open()) {
Expand Down
2 changes: 0 additions & 2 deletions src/openMVG/multiview/rotation_averaging_test.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -68,7 +68,6 @@ TEST ( rotation_averaging, RotationLeastSquare_3_Camera)
const Mat3 R01 = RotationAroundZ(2.*M_PI/3.0); //120°
const Mat3 R12 = RotationAroundZ(2.*M_PI/3.0); //120°
const Mat3 R20 = RotationAroundZ(2.*M_PI/3.0); //120°
const Mat3 Id = Mat3::Identity();

std::vector<RelativeRotation > vec_relativeRotEstimate;
vec_relativeRotEstimate.push_back( RelativeRotation(0,1, R01));
Expand Down Expand Up @@ -170,7 +169,6 @@ TEST ( rotation_averaging, RefineRotationsAvgL1IRLS_SimpleTriplet)
const Mat3 R01 = RotationAroundZ(2.*M_PI/3.0); //120°
const Mat3 R12 = RotationAroundZ(2.*M_PI/3.0); //120°
const Mat3 R20 = RotationAroundZ(2.*M_PI/3.0); //120°
const Mat3 Id = Mat3::Identity();

// Setup the relative motions (relative rotations)
RelativeRotations vec_relativeRotEstimate;
Expand Down
Loading

0 comments on commit da7d51d

Please sign in to comment.