Functions and classes that are not dependant on scalar type are defined in this namespace. More...
Classes | |
struct | ConfigurationError |
An expception thrown when the yaml config file contains invalid configuration (e.g., mutually exclusive settings) More... | |
struct | ConverterToAndFromBytes |
struct | CurrentBibliography |
struct | FileLogger |
struct | Histogram |
struct | IdxCompare |
struct | InvalidElement |
An exception thrown when one tries to instanciate an element that does not exist in the registrar. More... | |
struct | InvalidModuleType |
An exception thrown when one tries to use a module type that does not exist. More... | |
struct | Logger |
The logger interface, used to output warnings and informations. More... | |
struct | NullLogger |
struct | Parametrizable |
The superclass of classes that are constructed using generic parameters. This class provides the parameter storage and fetching mechanism. More... | |
struct | Registrar |
A factor for subclasses of Interface. More... | |
struct | TransformationError |
An expection thrown when a transformation has invalid parameters. More... | |
Typedefs | |
typedef std::map< std::string, unsigned > | BibIndices |
typedef StringMapMap | Bibliography |
typedef std::map< std::string, std::vector< std::string > > | CsvElements |
Data from a CSV file. More... | |
typedef std::map< std::string, std::string > | StringMap |
typedef std::map< std::string, StringMap > | StringMapMap |
typedef std::vector< std::string > | StringVector |
typedef boost::timer | timer |
Functions | |
template<typename T > | |
static T | anyabs (const T &v) |
template<typename T > | |
size_t | argMax (const typename PointMatcher< T >::Vector &v) |
static Bibliography | bibliography () |
template<typename T > | |
T | computeDensity (const typename PointMatcher< T >::Matrix &NN) |
template<typename T > | |
PointMatcher< T >::Vector | computeNormal (const typename PointMatcher< T >::Vector &eigenVa, const typename PointMatcher< T >::Matrix &eigenVe) |
template<typename M > | |
bool | contains (const M &m, const typename M::key_type &k) |
bool | FalseLexicalComparison (std::string, std::string) |
Return always false. More... | |
template<typename M > | |
const M::mapped_type & | get (const M &m, const typename M::key_type &k) |
std::string | getAndReplaceBibEntries (const std::string &, CurrentBibliography &curBib) |
void | getNameParamsFromYAML (const YAML::Node &module, std::string &name, Parametrizable::Parameters ¶ms) |
Retrieve name and parameters from a yaml node. More... | |
template<typename Target , typename Source > | |
Target | lexical_cast (const Source &arg) |
General case of lexical cast, use boost. More... | |
template<> | |
float | lexical_cast (const std::string &arg) |
Special case of lexical cast to float, use lexical_cast_scalar_to_string. More... | |
template<typename Target > | |
Target | lexical_cast_scalar_to_string (const char *&arg) |
Overloaded function for convenience. More... | |
template<typename Target > | |
Target | lexical_cast_scalar_to_string (const std::string &arg) |
A lexical casting function that is an improvements over boost::lexical_cast that can handle "inf", "-inf", "Nan" for float and doubles. More... | |
template<typename T > | |
std::vector< T > | lexical_cast_vector (const std::string &arg) |
Special case of lexical cast to std::vector<T> More... | |
template<typename T > | |
static T | normalizeAngle (T v) |
std::ostream & | operator<< (std::ostream &o, const Parametrizable &p) |
Dump the documentation of this object to a stream. More... | |
std::ostream & | operator<< (std::ostream &o, const Parametrizable::ParameterDoc &p) |
Dump the documentation of this parameter to a stream. More... | |
std::ostream & | operator<< (std::ostream &o, const Parametrizable::ParametersDoc &p) |
Dump the documentation of these parameters to a stream. More... | |
template<class T > | |
constexpr T | pow (const T base, const std::size_t exponent) |
template<typename DataType , typename MatrixRef > | |
std::istream & | readVtkData (bool readBinary, MatrixRef into, std::istream &in) |
template<typename MatrixRef > | |
std::istream & | readVtkData (std::string dataType, bool readBinary, MatrixRef into, std::istream &in) |
std::istream & | safeGetLine (std::istream &is, std::string &t) |
Replaces getline for handling windows style CR/LF line endings. More... | |
template<typename T > | |
PointMatcher< T >::Vector | serializeEigVec (const typename PointMatcher< T >::Matrix &eigenVe) |
void | setLogger (std::shared_ptr< Logger > newLogger) |
Set a new logger, protected by a mutex. More... | |
template<typename T > | |
PointMatcher< T >::Vector | sortEigenValues (const typename PointMatcher< T >::Vector &eigenVa) |
template<typename T > | |
std::vector< size_t > | sortIndexes (const typename PointMatcher< T >::Vector &v) |
template<typename S > | |
std::string | toParam (const S &value) |
Return the string value using lexical_cast. More... | |
template<typename T > | |
std::string | toParam (const std::vector< T > &input) |
Return the string value of a std::vector<T> More... | |
void | validateFile (const std::string &fileName) |
Throw a runtime_error exception if fileName cannot be opened. More... | |
template<typename Matrix > | |
std::ostream & | writeVtkData (bool writeBinary, const Matrix &data, std::ostream &out) |
Variables | |
const bool | isBigEndian = *reinterpret_cast<const unsigned char*>(&one) == static_cast<unsigned char>(0) |
true if platform is big endian More... | |
std::shared_ptr< Logger > | logger |
the current logger More... | |
boost::mutex | loggerMutex |
mutex to protect access to logging More... | |
const int | oneBigEndian = isBigEndian ? 1 : 1 << 8 * (sizeof(int) - 1) |
is always a big endian independent of the platforms endianness More... | |
Functions and classes that are not dependant on scalar type are defined in this namespace.
typedef std::map<std::string, unsigned> PointMatcherSupport::BibIndices |
Definition at line 49 of file Bibliography.h.
Definition at line 48 of file Bibliography.h.
typedef std::map<std::string, std::vector<std::string> > PointMatcherSupport::CsvElements |
Data from a CSV file.
Definition at line 125 of file PointMatcher.h.
typedef std::map<std::string, std::string> PointMatcherSupport::StringMap |
Definition at line 46 of file Bibliography.h.
typedef std::map<std::string, StringMap> PointMatcherSupport::StringMapMap |
Definition at line 47 of file Bibliography.h.
typedef std::vector<std::string> PointMatcherSupport::StringVector |
Definition at line 45 of file Bibliography.h.
typedef boost::timer PointMatcherSupport::timer |
|
inlinestatic |
Definition at line 44 of file Functions.h.
size_t PointMatcherSupport::argMax | ( | const typename PointMatcher< T >::Vector & | v | ) |
|
static |
Definition at line 66 of file Bibliography.cpp.
T PointMatcherSupport::computeDensity | ( | const typename PointMatcher< T >::Matrix & | NN | ) |
PointMatcher<T>::Vector PointMatcherSupport::computeNormal | ( | const typename PointMatcher< T >::Vector & | eigenVa, |
const typename PointMatcher< T >::Matrix & | eigenVe | ||
) |
bool PointMatcherSupport::contains | ( | const M & | m, |
const typename M::key_type & | k | ||
) |
Definition at line 50 of file Bibliography.cpp.
bool PointMatcherSupport::FalseLexicalComparison | ( | std::string | , |
std::string | |||
) |
Return always false.
Definition at line 77 of file Parametrizable.cpp.
const M::mapped_type& PointMatcherSupport::get | ( | const M & | m, |
const typename M::key_type & | k | ||
) |
Definition at line 57 of file Bibliography.cpp.
std::string PointMatcherSupport::getAndReplaceBibEntries | ( | const std::string & | , |
CurrentBibliography & | curBib | ||
) |
void PointMatcherSupport::getNameParamsFromYAML | ( | const YAML::Node & | module, |
std::string & | name, | ||
Parametrizable::Parameters & | params | ||
) |
Retrieve name and parameters from a yaml node.
Definition at line 7 of file Registrar.cpp.
|
inline |
General case of lexical cast, use boost.
Definition at line 77 of file Parametrizable.h.
|
inline |
Special case of lexical cast to float, use lexical_cast_scalar_to_string.
Definition at line 114 of file Parametrizable.h.
|
inline |
Overloaded function for convenience.
Definition at line 69 of file Parametrizable.h.
|
inline |
A lexical casting function that is an improvements over boost::lexical_cast that can handle "inf", "-inf", "Nan" for float and doubles.
Definition at line 55 of file Parametrizable.h.
|
inline |
Special case of lexical cast to std::vector<T>
Definition at line 84 of file Parametrizable.h.
|
inlinestatic |
Definition at line 53 of file Functions.h.
std::ostream& PointMatcherSupport::operator<< | ( | std::ostream & | o, |
const Parametrizable & | p | ||
) |
Dump the documentation of this object to a stream.
Definition at line 62 of file Parametrizable.cpp.
std::ostream& PointMatcherSupport::operator<< | ( | std::ostream & | o, |
const Parametrizable::ParameterDoc & | p | ||
) |
Dump the documentation of this parameter to a stream.
Definition at line 51 of file Parametrizable.cpp.
std::ostream & PointMatcherSupport::operator<< | ( | std::ostream & | o, |
const Parametrizable::ParametersDoc & | p | ||
) |
Dump the documentation of these parameters to a stream.
Definition at line 69 of file Parametrizable.cpp.
|
inlineconstexpr |
std::istream& PointMatcherSupport::readVtkData | ( | bool | readBinary, |
MatrixRef | into, | ||
std::istream & | in | ||
) |
Definition at line 108 of file IOFunctions.h.
std::istream& PointMatcherSupport::readVtkData | ( | std::string | dataType, |
bool | readBinary, | ||
MatrixRef | into, | ||
std::istream & | in | ||
) |
Definition at line 137 of file IOFunctions.h.
std::istream & PointMatcherSupport::safeGetLine | ( | std::istream & | is, |
std::string & | t | ||
) |
Replaces getline for handling windows style CR/LF line endings.
Definition at line 7 of file IOFunctions.cpp.
PointMatcher<T>::Vector PointMatcherSupport::serializeEigVec | ( | const typename PointMatcher< T >::Matrix & | eigenVe | ) |
void PointMatcherSupport::setLogger | ( | std::shared_ptr< Logger > | newLogger | ) |
Set a new logger, protected by a mutex.
Definition at line 98 of file Logger.cpp.
PointMatcher<T>::Vector PointMatcherSupport::sortEigenValues | ( | const typename PointMatcher< T >::Vector & | eigenVa | ) |
std::vector<size_t> PointMatcherSupport::sortIndexes | ( | const typename PointMatcher< T >::Vector & | v | ) |
|
inline |
Return the string value using lexical_cast.
Definition at line 123 of file Parametrizable.h.
|
inline |
Return the string value of a std::vector<T>
Definition at line 130 of file Parametrizable.h.
void PointMatcherSupport::validateFile | ( | const std::string & | fileName | ) |
Throw a runtime_error exception if fileName cannot be opened.
Definition at line 355 of file pointmatcher/IO.cpp.
std::ostream& PointMatcherSupport::writeVtkData | ( | bool | writeBinary, |
const Matrix & | data, | ||
std::ostream & | out | ||
) |
Definition at line 81 of file IOFunctions.h.
const bool PointMatcherSupport::isBigEndian = *reinterpret_cast<const unsigned char*>(&one) == static_cast<unsigned char>(0) |
true if platform is big endian
Definition at line 62 of file pointmatcher/IO.cpp.
std::shared_ptr< Logger > PointMatcherSupport::logger |
boost::mutex PointMatcherSupport::loggerMutex |
mutex to protect access to logging
Mutex to protect creation and deletion of logger.
Definition at line 41 of file Logger.cpp.
const int PointMatcherSupport::oneBigEndian = isBigEndian ? 1 : 1 << 8 * (sizeof(int) - 1) |
is always a big endian independent of the platforms endianness
Definition at line 63 of file pointmatcher/IO.cpp.