Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Add scale as parameter in functions for sfm #736

Merged
merged 5 commits into from
Mar 25, 2020
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -10,6 +10,7 @@
#include "aliceVision/colorHarmonization/CommonDataByPair.hpp"
#include "aliceVision/matching/IndMatch.hpp"
#include "aliceVision/feature/feature.hpp"
#include "aliceVision/feature/RegionsPerView.hpp"

#include <vector>

Expand Down Expand Up @@ -53,8 +54,8 @@ class CommonDataByPair_matchedPoints : public CommonDataByPair

for(const matching::IndMatch& match : matchesPerDescIt.second) //< loop over matches
{
const feature::SIOPointFeature& L = feature::getSIOPointFeatures(*_regionsL.at(descType)).at(match._i);
const feature::SIOPointFeature& R = feature::getSIOPointFeatures(*_regionsR.at(descType)).at(match._j);
const feature::PointFeature& L = _regionsL.at(descType)->Features().at(match._i);
const feature::PointFeature& R = _regionsR.at(descType)->Features().at(match._j);

image::FilledCircle( L.x(), L.y(), ( int )_radius, ( unsigned char ) 255, &maskLeft );
image::FilledCircle( R.x(), R.y(), ( int )_radius, ( unsigned char ) 255, &maskRight );
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -20,8 +20,8 @@ class CommonDataByPair_vldSegment : public CommonDataByPair
CommonDataByPair_vldSegment( const std::string& sLeftImage,
const std::string& sRightImage,
const matching::IndMatches& matchesPerDesc,
const std::vector<feature::SIOPointFeature>& featsL,
const std::vector<feature::SIOPointFeature>& featsR)
const std::vector<feature::PointFeature>& featsL,
const std::vector<feature::PointFeature>& featsR)
: CommonDataByPair( sLeftImage, sRightImage )
, _matches( matchesPerDesc )
, _featsL( featsL )
Expand Down Expand Up @@ -104,8 +104,8 @@ class CommonDataByPair_vldSegment : public CommonDataByPair

private:
// Left and Right features
const std::vector<feature::SIOPointFeature>& _featsL;
const std::vector<feature::SIOPointFeature>& _featsR;
const std::vector<feature::PointFeature>& _featsL;
const std::vector<feature::PointFeature>& _featsR;
// Left and Right corresponding index (putatives matches)
matching::IndMatches _matches;
};
Expand Down
2 changes: 1 addition & 1 deletion src/aliceVision/feature/KeypointSet.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@ namespace feature {
/// Association storage of associated feature and descriptor for a given image.
/// Load, save, R/W accessor operation.
///
/// typedef vector<SIOPointFeature> featsT;
/// typedef vector<PointFeature> featsT;
/// typedef vector<Descriptor<uchar,128> > descsT;
/// KeypointSet< featsT, descsT > kpSet;
template<typename FeaturesT, typename DescriptorsT>
Expand Down
72 changes: 22 additions & 50 deletions src/aliceVision/feature/PointFeature.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -27,55 +27,26 @@ class PointFeature {
friend std::istream& operator>>(std::istream& in, PointFeature& obj);

public:
PointFeature(float x=0.0f, float y=0.0f)
: _coords(x, y) {}
PointFeature() {}
PointFeature(float x, float y, float scale, float orient)
: _coords(x, y),
_scale(scale),
_orientation(orient)
{}

float x() const { return _coords(0); }
float y() const { return _coords(1); }
const Vec2f & coords() const { return _coords;}
float scale() const { return _scale; }
float& scale() { return _scale; }

float& x() { return _coords(0); }
float& y() { return _coords(1); }
Vec2f& coords() { return _coords;}

protected:
Vec2f _coords; // (x, y)
};

typedef std::vector<PointFeature> PointFeatures;

//with overloaded operators:
inline std::ostream& operator<<(std::ostream& out, const PointFeature& obj)
{
return out << obj._coords(0) << " " << obj._coords(1);
}

inline std::istream& operator>>(std::istream& in, PointFeature& obj)
{
return in >> obj._coords(0) >> obj._coords(1);
}

/**
* Base class for ScaleInvariant Oriented Point features.
* Add scale and orientation description to basis PointFeature.
*/
class SIOPointFeature : public PointFeature {

friend std::ostream& operator<<(std::ostream& out, const SIOPointFeature& obj);
friend std::istream& operator>>(std::istream& in, SIOPointFeature& obj);

public:
SIOPointFeature(float x=0.0f, float y=0.0f,
float scale=0.0f, float orient=0.0f)
: PointFeature(x,y)
, _scale(scale)
, _orientation(orient) {}

float scale() const { return _scale; }
float& scale() { return _scale; }
float orientation() const { return _orientation; }
float& orientation() { return _orientation; }

/**
* @brief Return the orientation of the feature as an unit vector.
* @return a unit vector corresponding to the orientation of the feature.
Expand All @@ -93,33 +64,34 @@ class SIOPointFeature : public PointFeature {
{
return scale()*getOrientationVector();
}
bool operator ==(const SIOPointFeature& b) const {

bool operator ==(const PointFeature& b) const {
return (_scale == b.scale()) &&
(_orientation == b.orientation()) &&
(x() == b.x()) && (y() == b.y()) ;
}

bool operator !=(const SIOPointFeature& b) const {
bool operator !=(const PointFeature& b) const {
return !((*this)==b);
}

protected:
float _scale; // In pixels.
float _orientation; // In radians.
Vec2f _coords = {0.0f, 0.0f}; // (x, y)
float _scale = 0.0f; // In pixels.
float _orientation = 0.0f; // In radians.
};

//
inline std::ostream& operator<<(std::ostream& out, const SIOPointFeature& obj)
typedef std::vector<PointFeature> PointFeatures;

//with overloaded operators:
inline std::ostream& operator<<(std::ostream& out, const PointFeature& obj)
{
const PointFeature *pf = static_cast<const PointFeature*>(&obj);
return out << *pf << " " << obj._scale << " " << obj._orientation;
return out << obj._coords(0) << " " << obj._coords(1) << " " << obj._scale << " " << obj._orientation;
}

inline std::istream& operator>>(std::istream& in, SIOPointFeature& obj)
inline std::istream& operator>>(std::istream& in, PointFeature& obj)
{
PointFeature *pf = static_cast<PointFeature*>(&obj);
return in >> *pf >> obj._scale >> obj._orientation;
return in >> obj._coords(0) >> obj._coords(1) >> obj._scale >> obj._orientation;
}

/// Read feats from file
Expand Down
105 changes: 38 additions & 67 deletions src/aliceVision/feature/Regions.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,7 @@ namespace aliceVision {
namespace feature {

/**
* @brief Store a featureIndes and the associated point3dId
* @brief Store a featureIndex and the associated point3dId
*/
struct FeatureInImage
{
Expand All @@ -43,12 +43,42 @@ struct FeatureInImage

/// Describe an image a set of regions (position, ...) + attributes
/// Each region is described by a set of attributes (descriptor)
/**
* @brief The Regions class describe a set of regions extracted from an image.
* It contains both a feature (position, scale, orientation) and a descriptor (photometric neighborhood description).
*/
class Regions
{
public:

virtual ~Regions() = 0;

protected:
std::vector<PointFeature> _vec_feats; // region features

public:
void LoadFeatures(const std::string& sfileNameFeats)
{
loadFeatsFromFile(sfileNameFeats, _vec_feats);
}

PointFeatures GetRegionsPositions() const
{
return PointFeatures(_vec_feats.begin(), _vec_feats.end());
}

Vec2 GetRegionPosition(std::size_t i) const
{
return Vec2f(_vec_feats[i].coords()).cast<double>();
}

/// Return the number of defined regions
std::size_t RegionCount() const {return _vec_feats.size();}

/// Mutable and non-mutable PointFeature getters.
inline std::vector<PointFeature> & Features() { return _vec_feats; }
inline const std::vector<PointFeature> & Features() const { return _vec_feats; }

//--
// IO - one file for region features, one file for region descriptors
//--
Expand All @@ -63,9 +93,6 @@ class Regions

virtual void SaveDesc(const std::string& sfileNameDescs) const = 0;

virtual void LoadFeatures(
const std::string& sfileNameFeats) = 0;

//--
//- Basic description of a descriptor [Type, Length]
//--
Expand All @@ -76,13 +103,6 @@ class Regions
virtual std::string Type_id() const = 0;
virtual std::size_t DescriptorLength() const = 0;

//-- Assume that a region can always be represented at least by a 2D positions
virtual PointFeatures GetRegionsPositions() const = 0;
virtual Vec2 GetRegionPosition(std::size_t i) const = 0;

/// Return the number of defined regions
virtual std::size_t RegionCount() const = 0;

/**
* @brief Return a blind pointer to the container of the descriptors array.
*
Expand Down Expand Up @@ -119,55 +139,6 @@ class Regions

inline Regions::~Regions() {}

template<typename FeatT>
class FeatRegions : public Regions
{
public:
/// Region type
typedef FeatT FeatureT;
/// Container for multiple regions
typedef std::vector<FeatureT> FeatsT;

virtual ~FeatRegions() {}

protected:
std::vector<FeatureT> _vec_feats; // region features

public:
void LoadFeatures(const std::string& sfileNameFeats)
{
loadFeatsFromFile(sfileNameFeats, _vec_feats);
}

PointFeatures GetRegionsPositions() const
{
return PointFeatures(_vec_feats.begin(), _vec_feats.end());
}

Vec2 GetRegionPosition(std::size_t i) const
{
return Vec2f(_vec_feats[i].coords()).cast<double>();
}

/// Return the number of defined regions
std::size_t RegionCount() const {return _vec_feats.size();}

/// Mutable and non-mutable FeatureT getters.
inline std::vector<FeatureT> & Features() { return _vec_feats; }
inline const std::vector<FeatureT> & Features() const { return _vec_feats; }
};

inline const std::vector<SIOPointFeature>& getSIOPointFeatures(const Regions& regions)
{
static const std::vector<SIOPointFeature> emptyFeats;

const FeatRegions<SIOPointFeature>* sioFeatures = dynamic_cast<const FeatRegions<SIOPointFeature>*>(&regions);
if(sioFeatures == nullptr)
return emptyFeats;
return sioFeatures->Features();
}


enum class ERegionType: bool
{
Binary = 0,
Expand All @@ -191,11 +162,11 @@ struct SquaredMetric<T, ERegionType::Binary>
};


template<typename FeatT, typename T, std::size_t L, ERegionType regionType>
class FeatDescRegions : public FeatRegions<FeatT>
template<typename T, std::size_t L, ERegionType regionType>
class FeatDescRegions : public Regions
{
public:
typedef FeatDescRegions<FeatT, T, L, regionType> This;
typedef FeatDescRegions<T, L, regionType> This;
/// Region descriptor
typedef Descriptor<T, L> DescriptorT;
/// Container for multiple regions description
Expand Down Expand Up @@ -318,11 +289,11 @@ class FeatDescRegions : public FeatRegions<FeatT>
};


template<typename FeatT, typename T, std::size_t L>
using ScalarRegions = FeatDescRegions<FeatT, T, L, ERegionType::Scalar>;
template<typename T, std::size_t L>
using ScalarRegions = FeatDescRegions<T, L, ERegionType::Scalar>;

template<typename FeatT, std::size_t L>
using BinaryRegions = FeatDescRegions<FeatT, unsigned char, L, ERegionType::Binary>;
template<std::size_t L>
using BinaryRegions = FeatDescRegions<unsigned char, L, ERegionType::Binary>;



Expand Down
8 changes: 4 additions & 4 deletions src/aliceVision/feature/akaze/ImageDescriber_AKAZE.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -63,7 +63,7 @@ bool ImageDescriber_AKAZE::describe(const image::Image<float>& image,
point.angle = 0.0f;

regionsCasted->Features()[i] =
SIOPointFeature(point.x, point.y, point.size, point.angle);
PointFeature(point.x, point.y, point.size, point.angle);

ComputeMSURFDescriptor(cur_slice.Lx, cur_slice.Ly, point.octave,
regionsCasted->Features()[i],
Expand Down Expand Up @@ -102,12 +102,12 @@ bool ImageDescriber_AKAZE::describe(const image::Image<float>& image,
point.angle = 0.0f;

regionsCasted->Features()[i] =
SIOPointFeature(point.x, point.y, point.size, point.angle);
PointFeature(point.x, point.y, point.size, point.angle);

// compute LIOP descriptor (do not need rotation computation, since
// LIOP descriptor is rotation invariant).
// rescale for LIOP patch extraction
const SIOPointFeature fp = SIOPointFeature(point.x, point.y, point.size/2.0, point.angle);
const PointFeature fp = PointFeature(point.x, point.y, point.size/2.0, point.angle);

float desc[144];
liop_extractor.extract(image, fp, desc);
Expand Down Expand Up @@ -143,7 +143,7 @@ bool ImageDescriber_AKAZE::describe(const image::Image<float>& image,
else
point.angle = 0.0f;

regionsCasted->Features()[i] = SIOPointFeature(point.x, point.y, point.size, point.angle);
regionsCasted->Features()[i] = PointFeature(point.x, point.y, point.size, point.angle);

// compute MLDB descriptor
Descriptor<bool,486> desc;
Expand Down
2 changes: 1 addition & 1 deletion src/aliceVision/feature/akaze/descriptorLIOP.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -287,7 +287,7 @@ void DescriptorExtractor_LIOP::CreateLIOP_GOrder(

void DescriptorExtractor_LIOP::extract(
const image::Image<float>& I,
const SIOPointFeature& feat,
const PointFeature& feat,
float desc[144])
{
memset(desc, 0, sizeof(float)*144);
Expand Down
2 changes: 1 addition & 1 deletion src/aliceVision/feature/akaze/descriptorLIOP.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -45,7 +45,7 @@ class DescriptorExtractor_LIOP

void extract(
const image::Image<float> & I,
const SIOPointFeature & feat,
const PointFeature & feat,
float desc[144]);

void CreateLIOP_GOrder(
Expand Down
2 changes: 1 addition & 1 deletion src/aliceVision/feature/akaze/descriptorMLDB.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -145,7 +145,7 @@ namespace feature {
const image::Image<Real> &Lx,
const image::Image<Real> &Ly,
const int id_octave ,
const SIOPointFeature & ipt ,
const PointFeature & ipt ,
Descriptor<bool, 486> & desc )
{
// // Note : in KAZE description we compute descriptor of previous slice and never the current one
Expand Down
Loading