Merged in fix/serialization_warnings (pull request #128)

Fix some unused variable warnings in the serialization code.
release/4.3a0
Chris Beall 2015-04-20 15:00:45 -04:00
commit b52ced7a09
123 changed files with 192 additions and 191 deletions

View File

@ -53,9 +53,10 @@ if(NOT FIRST_PASS_DONE)
endif() endif()
endif() endif()
# Clang on Mac uses a template depth that is less than standard and is too small # Clang uses a template depth that is less than standard and is too small
if(${CMAKE_CXX_COMPILER_ID} STREQUAL "Clang") if(${CMAKE_CXX_COMPILER_ID} STREQUAL "Clang")
if(NOT "${CMAKE_CXX_COMPILER_VERSION}" VERSION_LESS "5.0") # Apple Clang before 5.0 does not support -ftemplate-depth.
if(NOT (APPLE AND "${CMAKE_CXX_COMPILER_VERSION}" VERSION_LESS "5.0"))
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -ftemplate-depth=1024") set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -ftemplate-depth=1024")
endif() endif()
endif() endif()

View File

@ -95,7 +95,7 @@ private:
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class Archive> template<class Archive>
void save(Archive& ar, const unsigned int version) const void save(Archive& ar, const unsigned int /*version*/) const
{ {
// Copy to an STL container and serialize that // Copy to an STL container and serialize that
FastVector<std::pair<KEY, VALUE> > map(this->size()); FastVector<std::pair<KEY, VALUE> > map(this->size());
@ -103,7 +103,7 @@ private:
ar & BOOST_SERIALIZATION_NVP(map); ar & BOOST_SERIALIZATION_NVP(map);
} }
template<class Archive> template<class Archive>
void load(Archive& ar, const unsigned int version) void load(Archive& ar, const unsigned int /*version*/)
{ {
// Load into STL container and then fill our map // Load into STL container and then fill our map
FastVector<std::pair<KEY, VALUE> > map; FastVector<std::pair<KEY, VALUE> > map;

View File

@ -129,7 +129,7 @@ public:
protected: protected:
/// Assignment operator, protected because only the Value or DERIVED /// Assignment operator, protected because only the Value or DERIVED
/// assignment operators should be used. /// assignment operators should be used.
DerivedValue<DERIVED>& operator=(const DerivedValue<DERIVED>& rhs) { DerivedValue<DERIVED>& operator=(const DerivedValue<DERIVED>& /*rhs*/) {
// Nothing to do, do not call base class assignment operator // Nothing to do, do not call base class assignment operator
return *this; return *this;
} }

View File

@ -74,7 +74,7 @@ private:
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version) { void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base); ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
} }

View File

@ -70,7 +70,7 @@ private:
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version) { void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base); ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
} }
}; };

View File

@ -111,7 +111,7 @@ private:
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version) { void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base); ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
} }
}; };

View File

@ -95,7 +95,7 @@ private:
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version) { void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base); ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
} }

View File

@ -183,7 +183,7 @@ public:
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version) { void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
ar & boost::serialization::make_nvp("GenericValue", ar & boost::serialization::make_nvp("GenericValue",
boost::serialization::base_object<Value>(*this)); boost::serialization::base_object<Value>(*this));
ar & boost::serialization::make_nvp("value", value_); ar & boost::serialization::make_nvp("value", value_);

View File

@ -248,7 +248,7 @@ public:
// log and exp map without Jacobians // log and exp map without Jacobians
g = traits<T>::Expmap(v); g = traits<T>::Expmap(v);
v = traits<T>::Logmap(g); v = traits<T>::Logmap(g);
// log and expnential map with Jacobians // log and exponential map with Jacobians
g = traits<T>::Expmap(v, Hg); g = traits<T>::Expmap(v, Hg);
v = traits<T>::Logmap(g, Hg); v = traits<T>::Logmap(g, Hg);
} }

View File

@ -124,7 +124,7 @@ private:
// Serialization function // Serialization function
friend class boost::serialization::access; friend class boost::serialization::access;
template<class Archive> template<class Archive>
void serialize(Archive & ar, const unsigned int version) { void serialize(Archive & ar, const unsigned int /*version*/) {
ar & boost::serialization::make_nvp("Matrix", ar & boost::serialization::make_nvp("Matrix",
boost::serialization::base_object<Matrix>(*this)); boost::serialization::base_object<Matrix>(*this));

View File

@ -103,7 +103,7 @@ private:
// Serialization function // Serialization function
friend class boost::serialization::access; friend class boost::serialization::access;
template<class Archive> template<class Archive>
void serialize(Archive & ar, const unsigned int version) { void serialize(Archive & ar, const unsigned int /*version*/) {
ar & boost::serialization::make_nvp("Vector", ar & boost::serialization::make_nvp("Vector",
boost::serialization::base_object<Vector>(*this)); boost::serialization::base_object<Vector>(*this));
} }

View File

@ -535,7 +535,7 @@ namespace boost {
// split version - sends sizes ahead // split version - sends sizes ahead
template<class Archive> template<class Archive>
void save(Archive & ar, const gtsam::Matrix & m, unsigned int version) { void save(Archive & ar, const gtsam::Matrix & m, unsigned int /*version*/) {
const size_t rows = m.rows(), cols = m.cols(); const size_t rows = m.rows(), cols = m.cols();
ar << BOOST_SERIALIZATION_NVP(rows); ar << BOOST_SERIALIZATION_NVP(rows);
ar << BOOST_SERIALIZATION_NVP(cols); ar << BOOST_SERIALIZATION_NVP(cols);
@ -543,7 +543,7 @@ namespace boost {
} }
template<class Archive> template<class Archive>
void load(Archive & ar, gtsam::Matrix & m, unsigned int version) { void load(Archive & ar, gtsam::Matrix & m, unsigned int /*version*/) {
size_t rows, cols; size_t rows, cols;
ar >> BOOST_SERIALIZATION_NVP(rows); ar >> BOOST_SERIALIZATION_NVP(rows);
ar >> BOOST_SERIALIZATION_NVP(cols); ar >> BOOST_SERIALIZATION_NVP(cols);

View File

@ -83,7 +83,7 @@ public:
#ifndef OPTIONALJACOBIAN_NOBOOST #ifndef OPTIONALJACOBIAN_NOBOOST
/// Constructor with boost::none just makes empty /// Constructor with boost::none just makes empty
OptionalJacobian(boost::none_t none) : OptionalJacobian(boost::none_t /*none*/) :
map_(NULL) { map_(NULL) {
} }
@ -142,7 +142,7 @@ public:
#ifndef OPTIONALJACOBIAN_NOBOOST #ifndef OPTIONALJACOBIAN_NOBOOST
/// Constructor with boost::none just makes empty /// Constructor with boost::none just makes empty
OptionalJacobian(boost::none_t none) : OptionalJacobian(boost::none_t /*none*/) :
pointer_(NULL) { pointer_(NULL) {
} }

View File

@ -199,6 +199,7 @@ namespace gtsam {
void checkBlock(DenseIndex block) const void checkBlock(DenseIndex block) const
{ {
static_cast<void>(block); //Disable unused varibale warnings.
assert(matrix_.rows() == matrix_.cols()); assert(matrix_.rows() == matrix_.cols());
assert(matrix_.cols() == variableColOffsets_.back()); assert(matrix_.cols() == variableColOffsets_.back());
assert(block >= 0); assert(block >= 0);
@ -235,7 +236,7 @@ namespace gtsam {
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version) { void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
// Fill in the lower triangle part of the matrix, so boost::serialization won't // Fill in the lower triangle part of the matrix, so boost::serialization won't
// complain about uninitialized data with an input_stream_error exception // complain about uninitialized data with an input_stream_error exception
// http://www.boost.org/doc/libs/1_37_0/libs/serialization/doc/exceptions.html#stream_error // http://www.boost.org/doc/libs/1_37_0/libs/serialization/doc/exceptions.html#stream_error

View File

@ -93,7 +93,7 @@ namespace gtsam
/// Create a SymmetricBlockMatrixBlockExpr from the specified range of blocks of a /// Create a SymmetricBlockMatrixBlockExpr from the specified range of blocks of a
/// SymmetricBlockMatrix. /// SymmetricBlockMatrix.
SymmetricBlockMatrixBlockExpr(SymmetricBlockMatrixType& blockMatrix, Index firstBlock, Index blocks, char dummy) : SymmetricBlockMatrixBlockExpr(SymmetricBlockMatrixType& blockMatrix, Index firstBlock, Index blocks, char /*dummy*/) :
xpr_(blockMatrix), myBlock_(blockMatrix.matrix_.block(0, 0, 0, 0)) xpr_(blockMatrix), myBlock_(blockMatrix.matrix_.block(0, 0, 0, 0))
{ {
initIndices(firstBlock, firstBlock, blocks, blocks); initIndices(firstBlock, firstBlock, blocks, blocks);

View File

@ -121,7 +121,7 @@ namespace gtsam {
virtual Vector localCoordinates_(const Value& value) const = 0; virtual Vector localCoordinates_(const Value& value) const = 0;
/** Assignment operator */ /** Assignment operator */
virtual Value& operator=(const Value& rhs) { virtual Value& operator=(const Value& /*rhs*/) {
//needs a empty definition so recursion in implicit derived assignment operators work //needs a empty definition so recursion in implicit derived assignment operators work
return *this; return *this;
} }
@ -166,7 +166,7 @@ namespace gtsam {
* */ * */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version) { void serialize(ARCHIVE & /*ar*/, const unsigned int /*version*/) {
} }
}; };

View File

@ -355,14 +355,14 @@ namespace boost {
// split version - copies into an STL vector for serialization // split version - copies into an STL vector for serialization
template<class Archive> template<class Archive>
void save(Archive & ar, const gtsam::Vector & v, unsigned int version) { void save(Archive & ar, const gtsam::Vector & v, unsigned int /*version*/) {
const size_t size = v.size(); const size_t size = v.size();
ar << BOOST_SERIALIZATION_NVP(size); ar << BOOST_SERIALIZATION_NVP(size);
ar << make_nvp("data", make_array(v.data(), v.size())); ar << make_nvp("data", make_array(v.data(), v.size()));
} }
template<class Archive> template<class Archive>
void load(Archive & ar, gtsam::Vector & v, unsigned int version) { void load(Archive & ar, gtsam::Vector & v, unsigned int /*version*/) {
size_t size; size_t size;
ar >> BOOST_SERIALIZATION_NVP(size); ar >> BOOST_SERIALIZATION_NVP(size);
v.resize(size); v.resize(size);
@ -371,12 +371,12 @@ namespace boost {
// split version - copies into an STL vector for serialization // split version - copies into an STL vector for serialization
template<class Archive, int D> template<class Archive, int D>
void save(Archive & ar, const Eigen::Matrix<double,D,1> & v, unsigned int version) { void save(Archive & ar, const Eigen::Matrix<double,D,1> & v, unsigned int /*version*/) {
ar << make_nvp("data", make_array(v.data(), v.RowsAtCompileTime)); ar << make_nvp("data", make_array(v.data(), v.RowsAtCompileTime));
} }
template<class Archive, int D> template<class Archive, int D>
void load(Archive & ar, Eigen::Matrix<double,D,1> & v, unsigned int version) { void load(Archive & ar, Eigen::Matrix<double,D,1> & v, unsigned int /*version*/) {
ar >> make_nvp("data", make_array(v.data(), v.RowsAtCompileTime)); ar >> make_nvp("data", make_array(v.data(), v.RowsAtCompileTime));
} }

View File

@ -401,7 +401,8 @@ struct DynamicTraits {
return result; return result;
} }
static Dynamic Expmap(const TangentVector& v, ChartJacobian H = boost::none) { static Dynamic Expmap(const TangentVector& /*v*/, ChartJacobian H = boost::none) {
static_cast<void>(H);
throw std::runtime_error("Expmap not defined for dynamic types"); throw std::runtime_error("Expmap not defined for dynamic types");
} }

View File

@ -199,6 +199,7 @@ namespace gtsam {
} }
void checkBlock(DenseIndex block) const { void checkBlock(DenseIndex block) const {
static_cast<void>(block); //Disable unused varibale warnings.
assert(matrix_.cols() == variableColOffsets_.back()); assert(matrix_.cols() == variableColOffsets_.back());
assert(block < (DenseIndex)variableColOffsets_.size() - 1); assert(block < (DenseIndex)variableColOffsets_.size() - 1);
assert(variableColOffsets_[block] < matrix_.cols() && variableColOffsets_[block+1] <= matrix_.cols()); assert(variableColOffsets_[block] < matrix_.cols() && variableColOffsets_[block+1] <= matrix_.cols());
@ -220,7 +221,7 @@ namespace gtsam {
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version) { void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
ar & BOOST_SERIALIZATION_NVP(matrix_); ar & BOOST_SERIALIZATION_NVP(matrix_);
ar & BOOST_SERIALIZATION_NVP(variableColOffsets_); ar & BOOST_SERIALIZATION_NVP(variableColOffsets_);
ar & BOOST_SERIALIZATION_NVP(rowStart_); ar & BOOST_SERIALIZATION_NVP(rowStart_);

View File

@ -90,7 +90,7 @@ namespace gtsam {
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version) { void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base); ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
} }
}; };

View File

@ -159,7 +159,7 @@ private:
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class Archive> template<class Archive>
void serialize(Archive & ar, const unsigned int version) { void serialize(Archive & ar, const unsigned int /*version*/) {
ar & BOOST_SERIALIZATION_NVP(f_); ar & BOOST_SERIALIZATION_NVP(f_);
ar & BOOST_SERIALIZATION_NVP(k1_); ar & BOOST_SERIALIZATION_NVP(k1_);
ar & BOOST_SERIALIZATION_NVP(k2_); ar & BOOST_SERIALIZATION_NVP(k2_);

View File

@ -109,7 +109,7 @@ private:
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class Archive> template<class Archive>
void serialize(Archive & ar, const unsigned int version) void serialize(Archive & ar, const unsigned int /*version*/)
{ {
ar & boost::serialization::make_nvp("Cal3DS2", ar & boost::serialization::make_nvp("Cal3DS2",
boost::serialization::base_object<Cal3DS2_Base>(*this)); boost::serialization::base_object<Cal3DS2_Base>(*this));

View File

@ -153,7 +153,7 @@ private:
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class Archive> template<class Archive>
void serialize(Archive & ar, const unsigned int version) void serialize(Archive & ar, const unsigned int /*version*/)
{ {
ar & BOOST_SERIALIZATION_NVP(fx_); ar & BOOST_SERIALIZATION_NVP(fx_);
ar & BOOST_SERIALIZATION_NVP(fy_); ar & BOOST_SERIALIZATION_NVP(fy_);

View File

@ -134,7 +134,7 @@ private:
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class Archive> template<class Archive>
void serialize(Archive & ar, const unsigned int version) void serialize(Archive & ar, const unsigned int /*version*/)
{ {
ar & boost::serialization::make_nvp("Cal3Unified", ar & boost::serialization::make_nvp("Cal3Unified",
boost::serialization::base_object<Cal3DS2_Base>(*this)); boost::serialization::base_object<Cal3DS2_Base>(*this));

View File

@ -211,7 +211,7 @@ private:
/// Serialization function /// Serialization function
friend class boost::serialization::access; friend class boost::serialization::access;
template<class Archive> template<class Archive>
void serialize(Archive & ar, const unsigned int version) { void serialize(Archive & ar, const unsigned int /*version*/) {
ar & BOOST_SERIALIZATION_NVP(fx_); ar & BOOST_SERIALIZATION_NVP(fx_);
ar & BOOST_SERIALIZATION_NVP(fy_); ar & BOOST_SERIALIZATION_NVP(fy_);
ar & BOOST_SERIALIZATION_NVP(s_); ar & BOOST_SERIALIZATION_NVP(s_);

View File

@ -144,7 +144,7 @@ namespace gtsam {
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class Archive> template<class Archive>
void serialize(Archive & ar, const unsigned int version) void serialize(Archive & ar, const unsigned int /*version*/)
{ {
ar & BOOST_SERIALIZATION_NVP(K_); ar & BOOST_SERIALIZATION_NVP(K_);
ar & BOOST_SERIALIZATION_NVP(b_); ar & BOOST_SERIALIZATION_NVP(b_);

View File

@ -297,7 +297,7 @@ private:
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class Archive> template<class Archive>
void serialize(Archive & ar, const unsigned int version) { void serialize(Archive & ar, const unsigned int /*version*/) {
ar & BOOST_SERIALIZATION_NVP(pose_); ar & BOOST_SERIALIZATION_NVP(pose_);
} }
@ -449,7 +449,7 @@ private:
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class Archive> template<class Archive>
void serialize(Archive & ar, const unsigned int version) { void serialize(Archive & ar, const unsigned int /*version*/) {
ar ar
& boost::serialization::make_nvp("PinholeBase", & boost::serialization::make_nvp("PinholeBase",
boost::serialization::base_object<PinholeBase>(*this)); boost::serialization::base_object<PinholeBase>(*this));

View File

@ -104,7 +104,7 @@ private:
/// Serialization function /// Serialization function
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version) { void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
ar & (*this); ar & (*this);
} }
}; };

View File

@ -179,7 +179,7 @@ private:
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version) { void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
ar & BOOST_SERIALIZATION_NVP(aRb_); ar & BOOST_SERIALIZATION_NVP(aRb_);
ar & BOOST_SERIALIZATION_NVP(aTb_); ar & BOOST_SERIALIZATION_NVP(aTb_);

View File

@ -371,7 +371,7 @@ private:
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class Archive> template<class Archive>
void serialize(Archive & ar, const unsigned int version) { void serialize(Archive & ar, const unsigned int /*version*/) {
ar ar
& boost::serialization::make_nvp("PinholeBaseK", & boost::serialization::make_nvp("PinholeBaseK",
boost::serialization::base_object<Base>(*this)); boost::serialization::base_object<Base>(*this));

View File

@ -160,7 +160,7 @@ private:
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class Archive> template<class Archive>
void serialize(Archive & ar, const unsigned int version) { void serialize(Archive & ar, const unsigned int /*version*/) {
ar ar
& boost::serialization::make_nvp("PinholeBase", & boost::serialization::make_nvp("PinholeBase",
boost::serialization::base_object<PinholeBase>(*this)); boost::serialization::base_object<PinholeBase>(*this));
@ -321,7 +321,7 @@ private:
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class Archive> template<class Archive>
void serialize(Archive & ar, const unsigned int version) { void serialize(Archive & ar, const unsigned int /*version*/) {
ar ar
& boost::serialization::make_nvp("PinholeBaseK", & boost::serialization::make_nvp("PinholeBaseK",
boost::serialization::base_object<Base>(*this)); boost::serialization::base_object<Base>(*this));

View File

@ -185,7 +185,7 @@ private:
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version) void serialize(ARCHIVE & ar, const unsigned int /*version*/)
{ {
ar & BOOST_SERIALIZATION_NVP(x_); ar & BOOST_SERIALIZATION_NVP(x_);
ar & BOOST_SERIALIZATION_NVP(y_); ar & BOOST_SERIALIZATION_NVP(y_);

View File

@ -181,7 +181,7 @@ namespace gtsam {
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version) void serialize(ARCHIVE & ar, const unsigned int /*version*/)
{ {
ar & BOOST_SERIALIZATION_NVP(x_); ar & BOOST_SERIALIZATION_NVP(x_);
ar & BOOST_SERIALIZATION_NVP(y_); ar & BOOST_SERIALIZATION_NVP(y_);

View File

@ -271,7 +271,7 @@ private:
// Serialization function // Serialization function
friend class boost::serialization::access; friend class boost::serialization::access;
template<class Archive> template<class Archive>
void serialize(Archive & ar, const unsigned int version) { void serialize(Archive & ar, const unsigned int /*version*/) {
ar & BOOST_SERIALIZATION_NVP(t_); ar & BOOST_SERIALIZATION_NVP(t_);
ar & BOOST_SERIALIZATION_NVP(r_); ar & BOOST_SERIALIZATION_NVP(r_);
} }

View File

@ -294,7 +294,7 @@ private:
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class Archive> template<class Archive>
void serialize(Archive & ar, const unsigned int version) { void serialize(Archive & ar, const unsigned int /*version*/) {
ar & BOOST_SERIALIZATION_NVP(R_); ar & BOOST_SERIALIZATION_NVP(R_);
ar & BOOST_SERIALIZATION_NVP(t_); ar & BOOST_SERIALIZATION_NVP(t_);
} }

View File

@ -118,12 +118,12 @@ namespace gtsam {
Matrix1 AdjointMap() const { return I_1x1; } Matrix1 AdjointMap() const { return I_1x1; }
/// Left-trivialized derivative of the exponential map /// Left-trivialized derivative of the exponential map
static Matrix ExpmapDerivative(const Vector& v) { static Matrix ExpmapDerivative(const Vector& /*v*/) {
return ones(1); return ones(1);
} }
/// Left-trivialized derivative inverse of the exponential map /// Left-trivialized derivative inverse of the exponential map
static Matrix LogmapDerivative(const Vector& v) { static Matrix LogmapDerivative(const Vector& /*v*/) {
return ones(1); return ones(1);
} }
@ -200,7 +200,7 @@ namespace gtsam {
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version) { void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
ar & BOOST_SERIALIZATION_NVP(c_); ar & BOOST_SERIALIZATION_NVP(c_);
ar & BOOST_SERIALIZATION_NVP(s_); ar & BOOST_SERIALIZATION_NVP(s_);
} }

View File

@ -428,7 +428,7 @@ namespace gtsam {
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version) void serialize(ARCHIVE & ar, const unsigned int /*version*/)
{ {
#ifndef GTSAM_USE_QUATERNIONS #ifndef GTSAM_USE_QUATERNIONS
ar & boost::serialization::make_nvp("rot11", rot_(0,0)); ar & boost::serialization::make_nvp("rot11", rot_(0,0));

View File

@ -157,7 +157,7 @@ private:
friend class boost::serialization::access; friend class boost::serialization::access;
template<class Archive> template<class Archive>
void serialize(Archive & ar, const unsigned int version) { void serialize(Archive & ar, const unsigned int /*version*/) {
ar & BOOST_SERIALIZATION_NVP(leftCamPose_); ar & BOOST_SERIALIZATION_NVP(leftCamPose_);
ar & BOOST_SERIALIZATION_NVP(K_); ar & BOOST_SERIALIZATION_NVP(K_);
} }

View File

@ -164,7 +164,7 @@ namespace gtsam {
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version) { void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
ar & BOOST_SERIALIZATION_NVP(uL_); ar & BOOST_SERIALIZATION_NVP(uL_);
ar & BOOST_SERIALIZATION_NVP(uR_); ar & BOOST_SERIALIZATION_NVP(uR_);
ar & BOOST_SERIALIZATION_NVP(v_); ar & BOOST_SERIALIZATION_NVP(v_);

View File

@ -160,7 +160,7 @@ private:
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version) { void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
ar & BOOST_SERIALIZATION_NVP(p_); ar & BOOST_SERIALIZATION_NVP(p_);
// homebrew serialize Eigen Matrix // homebrew serialize Eigen Matrix
ar & boost::serialization::make_nvp("B11", (*B_)(0, 0)); ar & boost::serialization::make_nvp("B11", (*B_)(0, 0));

View File

@ -253,7 +253,7 @@ namespace gtsam {
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version) { void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
ar & BOOST_SERIALIZATION_NVP(nodes_); ar & BOOST_SERIALIZATION_NVP(nodes_);
ar & BOOST_SERIALIZATION_NVP(roots_); ar & BOOST_SERIALIZATION_NVP(roots_);
} }

View File

@ -160,7 +160,7 @@ namespace gtsam {
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version) { void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
ar & BOOST_SERIALIZATION_NVP(conditional_); ar & BOOST_SERIALIZATION_NVP(conditional_);
ar & BOOST_SERIALIZATION_NVP(parent_); ar & BOOST_SERIALIZATION_NVP(parent_);
ar & BOOST_SERIALIZATION_NVP(children); ar & BOOST_SERIALIZATION_NVP(children);

View File

@ -141,7 +141,7 @@ namespace gtsam {
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version) { void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
ar & BOOST_SERIALIZATION_NVP(nrFrontals_); ar & BOOST_SERIALIZATION_NVP(nrFrontals_);
} }

View File

@ -160,7 +160,7 @@ namespace gtsam {
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class Archive> template<class Archive>
void serialize(Archive & ar, const unsigned int version) { void serialize(Archive & ar, const unsigned int /*version*/) {
ar & BOOST_SERIALIZATION_NVP(keys_); ar & BOOST_SERIALIZATION_NVP(keys_);
} }

View File

@ -342,7 +342,7 @@ namespace gtsam {
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version) { void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
ar & BOOST_SERIALIZATION_NVP(factors_); ar & BOOST_SERIALIZATION_NVP(factors_);
} }

View File

@ -109,7 +109,7 @@ private:
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version) { void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
ar & BOOST_SERIALIZATION_NVP(c_); ar & BOOST_SERIALIZATION_NVP(c_);
ar & BOOST_SERIALIZATION_NVP(label_); ar & BOOST_SERIALIZATION_NVP(label_);
ar & BOOST_SERIALIZATION_NVP(j_); ar & BOOST_SERIALIZATION_NVP(j_);

View File

@ -187,7 +187,7 @@ namespace gtsam {
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version) { void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base); ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
} }
}; };

View File

@ -117,7 +117,7 @@ private:
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version) { void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
ar & BOOST_SERIALIZATION_NVP(c_); ar & BOOST_SERIALIZATION_NVP(c_);
ar & BOOST_SERIALIZATION_NVP(j_); ar & BOOST_SERIALIZATION_NVP(j_);
} }

View File

@ -166,7 +166,7 @@ namespace gtsam {
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version) { void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base); ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
} }
}; };

View File

@ -135,7 +135,7 @@ namespace gtsam {
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class Archive> template<class Archive>
void serialize(Archive & ar, const unsigned int version) { void serialize(Archive & ar, const unsigned int /*version*/) {
ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(BaseFactor); ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(BaseFactor);
ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(BaseConditional); ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(BaseConditional);
} }

View File

@ -135,7 +135,7 @@ namespace gtsam {
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version) { void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base); ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
} }

View File

@ -322,7 +322,7 @@ namespace gtsam {
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version) { void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base); ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
} }

View File

@ -434,7 +434,7 @@ namespace gtsam {
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version) { void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(GaussianFactor); ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(GaussianFactor);
ar & BOOST_SERIALIZATION_NVP(info_); ar & BOOST_SERIALIZATION_NVP(info_);
} }

View File

@ -349,7 +349,7 @@ namespace gtsam {
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version) { void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base); ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
ar & BOOST_SERIALIZATION_NVP(Ab_); ar & BOOST_SERIALIZATION_NVP(Ab_);
ar & BOOST_SERIALIZATION_NVP(model_); ar & BOOST_SERIALIZATION_NVP(model_);

View File

@ -116,7 +116,7 @@ namespace gtsam {
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version) { void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
ar & BOOST_SERIALIZATION_NVP(dim_); ar & BOOST_SERIALIZATION_NVP(dim_);
} }
}; };
@ -243,7 +243,7 @@ namespace gtsam {
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version) { void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base); ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
ar & BOOST_SERIALIZATION_NVP(sqrt_information_); ar & BOOST_SERIALIZATION_NVP(sqrt_information_);
} }
@ -338,7 +338,7 @@ namespace gtsam {
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version) { void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Gaussian); ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Gaussian);
ar & BOOST_SERIALIZATION_NVP(sigmas_); ar & BOOST_SERIALIZATION_NVP(sigmas_);
ar & BOOST_SERIALIZATION_NVP(invsigmas_); ar & BOOST_SERIALIZATION_NVP(invsigmas_);
@ -489,7 +489,7 @@ namespace gtsam {
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version) { void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Diagonal); ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Diagonal);
ar & BOOST_SERIALIZATION_NVP(mu_); ar & BOOST_SERIALIZATION_NVP(mu_);
} }
@ -556,7 +556,7 @@ namespace gtsam {
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version) { void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Diagonal); ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Diagonal);
ar & BOOST_SERIALIZATION_NVP(sigma_); ar & BOOST_SERIALIZATION_NVP(sigma_);
ar & BOOST_SERIALIZATION_NVP(invsigma_); ar & BOOST_SERIALIZATION_NVP(invsigma_);
@ -592,18 +592,18 @@ namespace gtsam {
virtual Vector whiten(const Vector& v) const { return v; } virtual Vector whiten(const Vector& v) const { return v; }
virtual Vector unwhiten(const Vector& v) const { return v; } virtual Vector unwhiten(const Vector& v) const { return v; }
virtual Matrix Whiten(const Matrix& H) const { return H; } virtual Matrix Whiten(const Matrix& H) const { return H; }
virtual void WhitenInPlace(Matrix& H) const {} virtual void WhitenInPlace(Matrix& /*H*/) const {}
virtual void WhitenInPlace(Eigen::Block<Matrix> H) const {} virtual void WhitenInPlace(Eigen::Block<Matrix> /*H*/) const {}
virtual void whitenInPlace(Vector& v) const {} virtual void whitenInPlace(Vector& /*v*/) const {}
virtual void unwhitenInPlace(Vector& v) const {} virtual void unwhitenInPlace(Vector& /*v*/) const {}
virtual void whitenInPlace(Eigen::Block<Vector>& v) const {} virtual void whitenInPlace(Eigen::Block<Vector>& /*v*/) const {}
virtual void unwhitenInPlace(Eigen::Block<Vector>& v) const {} virtual void unwhitenInPlace(Eigen::Block<Vector>& /*v*/) const {}
private: private:
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version) { void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Isotropic); ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Isotropic);
} }
}; };
@ -655,7 +655,7 @@ namespace gtsam {
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version) { void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
ar & BOOST_SERIALIZATION_NVP(reweight_); ar & BOOST_SERIALIZATION_NVP(reweight_);
} }
}; };
@ -667,16 +667,16 @@ namespace gtsam {
Null(const ReweightScheme reweight = Block) : Base(reweight) {} Null(const ReweightScheme reweight = Block) : Base(reweight) {}
virtual ~Null() {} virtual ~Null() {}
virtual double weight(const double &error) const { return 1.0; } virtual double weight(const double& /*error*/) const { return 1.0; }
virtual void print(const std::string &s) const; virtual void print(const std::string &s) const;
virtual bool equals(const Base& expected, const double tol=1e-8) const { return true; } virtual bool equals(const Base& /*expected*/, const double /*tol*/) const { return true; }
static shared_ptr Create() ; static shared_ptr Create() ;
private: private:
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version) { void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base); ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
} }
}; };
@ -700,7 +700,7 @@ namespace gtsam {
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version) { void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base); ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
ar & BOOST_SERIALIZATION_NVP(c_); ar & BOOST_SERIALIZATION_NVP(c_);
} }
@ -725,7 +725,7 @@ namespace gtsam {
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version) { void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base); ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
ar & BOOST_SERIALIZATION_NVP(k_); ar & BOOST_SERIALIZATION_NVP(k_);
} }
@ -754,7 +754,7 @@ namespace gtsam {
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version) { void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base); ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
ar & BOOST_SERIALIZATION_NVP(k_); ar & BOOST_SERIALIZATION_NVP(k_);
} }
@ -779,7 +779,7 @@ namespace gtsam {
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version) { void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base); ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
ar & BOOST_SERIALIZATION_NVP(c_); ar & BOOST_SERIALIZATION_NVP(c_);
} }
@ -804,7 +804,7 @@ namespace gtsam {
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version) { void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base); ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
ar & BOOST_SERIALIZATION_NVP(c_); ar & BOOST_SERIALIZATION_NVP(c_);
} }
@ -848,7 +848,7 @@ namespace gtsam {
// TODO: functions below are dummy but necessary for the noiseModel::Base // TODO: functions below are dummy but necessary for the noiseModel::Base
inline virtual Vector whiten(const Vector& v) const inline virtual Vector whiten(const Vector& v) const
{ Vector r = v; this->WhitenSystem(r); return r; } { Vector r = v; this->WhitenSystem(r); return r; }
inline virtual Vector unwhiten(const Vector& v) const inline virtual Vector unwhiten(const Vector& /*v*/) const
{ throw std::invalid_argument("unwhiten is not currently supported for robust noise models."); } { throw std::invalid_argument("unwhiten is not currently supported for robust noise models."); }
inline virtual double distance(const Vector& v) const inline virtual double distance(const Vector& v) const
{ return this->whiten(v).squaredNorm(); } { return this->whiten(v).squaredNorm(); }
@ -867,7 +867,7 @@ namespace gtsam {
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version) { void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base); ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
ar & boost::serialization::make_nvp("robust_", const_cast<RobustModel::shared_ptr&>(robust_)); ar & boost::serialization::make_nvp("robust_", const_cast<RobustModel::shared_ptr&>(robust_));
ar & boost::serialization::make_nvp("noise_", const_cast<NoiseModel::shared_ptr&>(noise_)); ar & boost::serialization::make_nvp("noise_", const_cast<NoiseModel::shared_ptr&>(noise_));

View File

@ -44,7 +44,7 @@ namespace gtsam {
private: private:
friend class boost::serialization::access; friend class boost::serialization::access;
template<class Archive> template<class Archive>
void serialize(Archive & ar, const unsigned int version) { void serialize(Archive & ar, const unsigned int /*version*/) {
ar & BOOST_SERIALIZATION_NVP(index_); ar & BOOST_SERIALIZATION_NVP(index_);
ar & BOOST_SERIALIZATION_NVP(weight_); ar & BOOST_SERIALIZATION_NVP(weight_);
} }
@ -85,7 +85,7 @@ namespace gtsam {
private: private:
friend class boost::serialization::access; friend class boost::serialization::access;
template<class Archive> template<class Archive>
void serialize(Archive & ar, const unsigned int version) { void serialize(Archive & ar, const unsigned int /*version*/) {
ar & BOOST_SERIALIZATION_NVP(edges_); ar & BOOST_SERIALIZATION_NVP(edges_);
} }
}; };

View File

@ -376,7 +376,7 @@ namespace gtsam {
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version) { void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
ar & BOOST_SERIALIZATION_NVP(values_); ar & BOOST_SERIALIZATION_NVP(values_);
} }
}; // VectorValues definition }; // VectorValues definition

View File

@ -97,7 +97,7 @@ public:
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version) { void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(PreintegratedRotation); ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(PreintegratedRotation);
ar & BOOST_SERIALIZATION_NVP(biasHat_); ar & BOOST_SERIALIZATION_NVP(biasHat_);
} }
@ -179,7 +179,7 @@ private:
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version) { void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
ar ar
& boost::serialization::make_nvp("NoiseModelFactor3", & boost::serialization::make_nvp("NoiseModelFactor3",
boost::serialization::base_object<Base>(*this)); boost::serialization::base_object<Base>(*this));

View File

@ -122,7 +122,7 @@ private:
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version) { void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
ar ar
& boost::serialization::make_nvp("NoiseModelFactor1", & boost::serialization::make_nvp("NoiseModelFactor1",
boost::serialization::base_object<Base>(*this)); boost::serialization::base_object<Base>(*this));
@ -206,7 +206,7 @@ private:
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version) { void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
ar ar
& boost::serialization::make_nvp("NoiseModelFactor1", & boost::serialization::make_nvp("NoiseModelFactor1",
boost::serialization::base_object<Base>(*this)); boost::serialization::base_object<Base>(*this));

View File

@ -147,7 +147,7 @@ public:
/// Serialization function /// Serialization function
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version) { void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(PreintegrationBase); ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(PreintegrationBase);
ar & BOOST_SERIALIZATION_NVP(preintMeasCov_); ar & BOOST_SERIALIZATION_NVP(preintMeasCov_);
} }
@ -246,9 +246,8 @@ private:
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version) { void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
ar ar & boost::serialization::make_nvp("NoiseModelFactor6",
& boost::serialization::make_nvp("NoiseModelFactor6",
boost::serialization::base_object<Base>(*this)); boost::serialization::base_object<Base>(*this));
ar & BOOST_SERIALIZATION_NVP(_PIM_); ar & BOOST_SERIALIZATION_NVP(_PIM_);
ar & BOOST_SERIALIZATION_NVP(gravity_); ar & BOOST_SERIALIZATION_NVP(gravity_);

View File

@ -103,7 +103,7 @@ private:
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version) { void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
ar ar
& boost::serialization::make_nvp("NoiseModelFactor1", & boost::serialization::make_nvp("NoiseModelFactor1",
boost::serialization::base_object<Base>(*this)); boost::serialization::base_object<Base>(*this));

View File

@ -200,7 +200,7 @@ private:
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version) { void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
ar & boost::serialization::make_nvp("imuBias::ConstantBias", *this); ar & boost::serialization::make_nvp("imuBias::ConstantBias", *this);
ar & BOOST_SERIALIZATION_NVP(biasAcc_); ar & BOOST_SERIALIZATION_NVP(biasAcc_);
ar & BOOST_SERIALIZATION_NVP(biasGyro_); ar & BOOST_SERIALIZATION_NVP(biasGyro_);
@ -208,9 +208,8 @@ private:
/// @} /// @}
}; }; // ConstantBias class
// ConstantBias class } // namespace imuBias
}// namespace imuBias
template<> template<>
struct traits<imuBias::ConstantBias> : public internal::VectorSpace< struct traits<imuBias::ConstantBias> : public internal::VectorSpace<

View File

@ -130,7 +130,7 @@ public:
/// Serialization function /// Serialization function
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version) { void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(PreintegrationBase); ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(PreintegrationBase);
ar & BOOST_SERIALIZATION_NVP(preintMeasCov_); ar & BOOST_SERIALIZATION_NVP(preintMeasCov_);
} }
@ -226,9 +226,8 @@ private:
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version) { void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
ar ar & boost::serialization::make_nvp("NoiseModelFactor5",
& boost::serialization::make_nvp("NoiseModelFactor5",
boost::serialization::base_object<Base>(*this)); boost::serialization::base_object<Base>(*this));
ar & BOOST_SERIALIZATION_NVP(_PIM_); ar & BOOST_SERIALIZATION_NVP(_PIM_);
ar & BOOST_SERIALIZATION_NVP(gravity_); ar & BOOST_SERIALIZATION_NVP(gravity_);

View File

@ -68,7 +68,7 @@ public:
/// Needed for testable /// Needed for testable
//------------------------------------------------------------------------------ //------------------------------------------------------------------------------
void print(const std::string& s) const { void print(const std::string& /*s*/) const {
std::cout << " gravity: [ " << gravity_.transpose() << " ]" << std::endl; std::cout << " gravity: [ " << gravity_.transpose() << " ]" << std::endl;
std::cout << " omegaCoriolis: [ " << omegaCoriolis_.transpose() << " ]" std::cout << " omegaCoriolis: [ " << omegaCoriolis_.transpose() << " ]"
<< std::endl; << std::endl;

View File

@ -147,7 +147,7 @@ private:
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version) { void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
ar & BOOST_SERIALIZATION_NVP(deltaRij_); ar & BOOST_SERIALIZATION_NVP(deltaRij_);
ar & BOOST_SERIALIZATION_NVP(deltaTij_); ar & BOOST_SERIALIZATION_NVP(deltaTij_);
ar & BOOST_SERIALIZATION_NVP(delRdelBiasOmega_); ar & BOOST_SERIALIZATION_NVP(delRdelBiasOmega_);

View File

@ -436,7 +436,7 @@ private:
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version) { void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(PreintegratedRotation); ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(PreintegratedRotation);
ar & BOOST_SERIALIZATION_NVP(biasHat_); ar & BOOST_SERIALIZATION_NVP(biasHat_);
ar & BOOST_SERIALIZATION_NVP(deltaPij_); ar & BOOST_SERIALIZATION_NVP(deltaPij_);

View File

@ -404,7 +404,7 @@ private:
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version) { void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base); ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
ar & BOOST_SERIALIZATION_NVP(cachedFactor_); ar & BOOST_SERIALIZATION_NVP(cachedFactor_);
ar & BOOST_SERIALIZATION_NVP(gradientContribution_); ar & BOOST_SERIALIZATION_NVP(gradientContribution_);

View File

@ -146,7 +146,7 @@ private:
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version) { void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
ar & boost::serialization::make_nvp("NonlinearFactor", ar & boost::serialization::make_nvp("NonlinearFactor",
boost::serialization::base_object<Base>(*this)); boost::serialization::base_object<Base>(*this));
ar & BOOST_SERIALIZATION_NVP(factor_); ar & BOOST_SERIALIZATION_NVP(factor_);

View File

@ -185,7 +185,7 @@ private:
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version) { void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
ar ar
& boost::serialization::make_nvp("NoiseModelFactor1", & boost::serialization::make_nvp("NoiseModelFactor1",
boost::serialization::base_object<Base>(*this)); boost::serialization::base_object<Base>(*this));
@ -273,7 +273,7 @@ private:
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version) { void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
ar ar
& boost::serialization::make_nvp("NoiseModelFactor1", & boost::serialization::make_nvp("NoiseModelFactor1",
boost::serialization::base_object<Base>(*this)); boost::serialization::base_object<Base>(*this));
@ -337,7 +337,7 @@ private:
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version) { void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
ar ar
& boost::serialization::make_nvp("NoiseModelFactor2", & boost::serialization::make_nvp("NoiseModelFactor2",
boost::serialization::base_object<Base>(*this)); boost::serialization::base_object<Base>(*this));

View File

@ -112,7 +112,7 @@ public:
* when the constraint is *NOT* fulfilled. * when the constraint is *NOT* fulfilled.
* @return true if the constraint is active * @return true if the constraint is active
*/ */
virtual bool active(const Values& c) const { return true; } virtual bool active(const Values& /*c*/) const { return true; }
/** linearize to a GaussianFactor */ /** linearize to a GaussianFactor */
virtual boost::shared_ptr<GaussianFactor> virtual boost::shared_ptr<GaussianFactor>
@ -247,7 +247,7 @@ private:
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version) { void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
ar & boost::serialization::make_nvp("NonlinearFactor", ar & boost::serialization::make_nvp("NonlinearFactor",
boost::serialization::base_object<Base>(*this)); boost::serialization::base_object<Base>(*this));
ar & BOOST_SERIALIZATION_NVP(noiseModel_); ar & BOOST_SERIALIZATION_NVP(noiseModel_);
@ -325,7 +325,7 @@ private:
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version) { void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
ar & boost::serialization::make_nvp("NoiseModelFactor", ar & boost::serialization::make_nvp("NoiseModelFactor",
boost::serialization::base_object<Base>(*this)); boost::serialization::base_object<Base>(*this));
} }
@ -401,7 +401,7 @@ private:
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version) { void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
ar & boost::serialization::make_nvp("NoiseModelFactor", ar & boost::serialization::make_nvp("NoiseModelFactor",
boost::serialization::base_object<Base>(*this)); boost::serialization::base_object<Base>(*this));
} }
@ -478,7 +478,7 @@ private:
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version) { void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
ar & boost::serialization::make_nvp("NoiseModelFactor", ar & boost::serialization::make_nvp("NoiseModelFactor",
boost::serialization::base_object<Base>(*this)); boost::serialization::base_object<Base>(*this));
} }
@ -559,7 +559,7 @@ private:
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version) { void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
ar & boost::serialization::make_nvp("NoiseModelFactor", ar & boost::serialization::make_nvp("NoiseModelFactor",
boost::serialization::base_object<Base>(*this)); boost::serialization::base_object<Base>(*this));
} }
@ -644,7 +644,7 @@ private:
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version) { void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
ar & boost::serialization::make_nvp("NoiseModelFactor", ar & boost::serialization::make_nvp("NoiseModelFactor",
boost::serialization::base_object<Base>(*this)); boost::serialization::base_object<Base>(*this));
} }
@ -733,7 +733,7 @@ private:
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version) { void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
ar & boost::serialization::make_nvp("NoiseModelFactor", ar & boost::serialization::make_nvp("NoiseModelFactor",
boost::serialization::base_object<Base>(*this)); boost::serialization::base_object<Base>(*this));
} }

View File

@ -155,7 +155,7 @@ namespace gtsam {
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version) { void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
ar & boost::serialization::make_nvp("NonlinearFactorGraph", ar & boost::serialization::make_nvp("NonlinearFactorGraph",
boost::serialization::base_object<Base>(*this)); boost::serialization::base_object<Base>(*this));
} }

View File

@ -398,7 +398,7 @@ namespace gtsam {
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version) { void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
ar & BOOST_SERIALIZATION_NVP(values_); ar & BOOST_SERIALIZATION_NVP(values_);
} }

View File

@ -109,7 +109,7 @@ namespace gtsam {
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version) { void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
ar & boost::serialization::make_nvp("AntiFactor", ar & boost::serialization::make_nvp("AntiFactor",
boost::serialization::base_object<Base>(*this)); boost::serialization::base_object<Base>(*this));
ar & BOOST_SERIALIZATION_NVP(factor_); ar & BOOST_SERIALIZATION_NVP(factor_);

View File

@ -91,7 +91,7 @@ namespace gtsam {
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version) { void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
ar & boost::serialization::make_nvp("NoiseModelFactor2", ar & boost::serialization::make_nvp("NoiseModelFactor2",
boost::serialization::base_object<Base>(*this)); boost::serialization::base_object<Base>(*this));
ar & BOOST_SERIALIZATION_NVP(measured_); ar & BOOST_SERIALIZATION_NVP(measured_);

View File

@ -113,7 +113,7 @@ namespace gtsam {
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version) { void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
ar & boost::serialization::make_nvp("NoiseModelFactor2", ar & boost::serialization::make_nvp("NoiseModelFactor2",
boost::serialization::base_object<Base>(*this)); boost::serialization::base_object<Base>(*this));
ar & BOOST_SERIALIZATION_NVP(measuredBearing_); ar & BOOST_SERIALIZATION_NVP(measuredBearing_);

View File

@ -117,7 +117,7 @@ namespace gtsam {
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version) { void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
ar & boost::serialization::make_nvp("NoiseModelFactor2", ar & boost::serialization::make_nvp("NoiseModelFactor2",
boost::serialization::base_object<Base>(*this)); boost::serialization::base_object<Base>(*this));
ar & BOOST_SERIALIZATION_NVP(measured_); ar & BOOST_SERIALIZATION_NVP(measured_);
@ -149,7 +149,7 @@ namespace gtsam {
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version) { void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
ar & boost::serialization::make_nvp("BetweenFactor", ar & boost::serialization::make_nvp("BetweenFactor",
boost::serialization::base_object<BetweenFactor<VALUE> >(*this)); boost::serialization::base_object<BetweenFactor<VALUE> >(*this));
} }

View File

@ -84,7 +84,7 @@ private:
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version) { void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
ar & boost::serialization::make_nvp("NoiseModelFactor1", ar & boost::serialization::make_nvp("NoiseModelFactor1",
boost::serialization::base_object<Base>(*this)); boost::serialization::base_object<Base>(*this));
ar & BOOST_SERIALIZATION_NVP(threshold_); ar & BOOST_SERIALIZATION_NVP(threshold_);
@ -157,7 +157,7 @@ private:
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version) { void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
ar & boost::serialization::make_nvp("NoiseModelFactor2", ar & boost::serialization::make_nvp("NoiseModelFactor2",
boost::serialization::base_object<Base>(*this)); boost::serialization::base_object<Base>(*this));
ar & BOOST_SERIALIZATION_NVP(threshold_); ar & BOOST_SERIALIZATION_NVP(threshold_);

View File

@ -97,7 +97,7 @@ private:
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version) { void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
ar ar
& boost::serialization::make_nvp("NoiseModelFactor2", & boost::serialization::make_nvp("NoiseModelFactor2",
boost::serialization::base_object<Base>(*this)); boost::serialization::base_object<Base>(*this));

View File

@ -120,7 +120,7 @@ namespace gtsam {
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class Archive> template<class Archive>
void serialize(Archive & ar, const unsigned int version) { void serialize(Archive & ar, const unsigned int /*version*/) {
ar & boost::serialization::make_nvp("NoiseModelFactor2", ar & boost::serialization::make_nvp("NoiseModelFactor2",
boost::serialization::base_object<Base>(*this)); boost::serialization::base_object<Base>(*this));
ar & BOOST_SERIALIZATION_NVP(measured_); ar & BOOST_SERIALIZATION_NVP(measured_);
@ -222,7 +222,7 @@ namespace gtsam {
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class Archive> template<class Archive>
void serialize(Archive & ar, const unsigned int version) { void serialize(Archive & ar, const unsigned int /*version*/) {
ar & boost::serialization::make_nvp("NoiseModelFactor3", ar & boost::serialization::make_nvp("NoiseModelFactor3",
boost::serialization::base_object<Base>(*this)); boost::serialization::base_object<Base>(*this));
ar & BOOST_SERIALIZATION_NVP(measured_); ar & BOOST_SERIALIZATION_NVP(measured_);

View File

@ -88,7 +88,7 @@ private:
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version) { void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
ar & boost::serialization::make_nvp("NoiseModelFactor1", ar & boost::serialization::make_nvp("NoiseModelFactor1",
boost::serialization::base_object<Base>(*this)); boost::serialization::base_object<Base>(*this));
ar & BOOST_SERIALIZATION_NVP(measured_); ar & BOOST_SERIALIZATION_NVP(measured_);

View File

@ -90,7 +90,7 @@ private:
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version) { void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
ar & boost::serialization::make_nvp("NoiseModelFactor1", ar & boost::serialization::make_nvp("NoiseModelFactor1",
boost::serialization::base_object<Base>(*this)); boost::serialization::base_object<Base>(*this));
ar & BOOST_SERIALIZATION_NVP(measured_); ar & BOOST_SERIALIZATION_NVP(measured_);

View File

@ -94,7 +94,7 @@ namespace gtsam {
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version) { void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
ar & boost::serialization::make_nvp("NoiseModelFactor1", ar & boost::serialization::make_nvp("NoiseModelFactor1",
boost::serialization::base_object<Base>(*this)); boost::serialization::base_object<Base>(*this));
ar & BOOST_SERIALIZATION_NVP(prior_); ar & BOOST_SERIALIZATION_NVP(prior_);

View File

@ -178,7 +178,7 @@ namespace gtsam {
/// Serialization function /// Serialization function
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version) { void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base); ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
ar & BOOST_SERIALIZATION_NVP(measured_); ar & BOOST_SERIALIZATION_NVP(measured_);
ar & BOOST_SERIALIZATION_NVP(K_); ar & BOOST_SERIALIZATION_NVP(K_);

View File

@ -90,7 +90,7 @@ private:
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version) { void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
ar ar
& boost::serialization::make_nvp("NoiseModelFactor2", & boost::serialization::make_nvp("NoiseModelFactor2",
boost::serialization::base_object<Base>(*this)); boost::serialization::base_object<Base>(*this));
@ -181,7 +181,7 @@ private:
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version) { void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
ar ar
& boost::serialization::make_nvp("NoiseModelFactor2", & boost::serialization::make_nvp("NoiseModelFactor2",
boost::serialization::base_object<Base>(*this)); boost::serialization::base_object<Base>(*this));

View File

@ -122,7 +122,7 @@ private:
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version) { void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
ar & boost::serialization::make_nvp("NonlinearFactor3", ar & boost::serialization::make_nvp("NonlinearFactor3",
boost::serialization::base_object<Base>(*this)); boost::serialization::base_object<Base>(*this));
} }

View File

@ -771,7 +771,7 @@ private:
/// Serialization function /// Serialization function
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version) { void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base); ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
ar & BOOST_SERIALIZATION_NVP(measured_); ar & BOOST_SERIALIZATION_NVP(measured_);
ar & BOOST_SERIALIZATION_NVP(body_P_sensor_); ar & BOOST_SERIALIZATION_NVP(body_P_sensor_);

View File

@ -687,7 +687,7 @@ private:
/// Serialization function /// Serialization function
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version) { void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base); ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
ar & BOOST_SERIALIZATION_NVP(throwCheirality_); ar & BOOST_SERIALIZATION_NVP(throwCheirality_);
ar & BOOST_SERIALIZATION_NVP(verboseCheirality_); ar & BOOST_SERIALIZATION_NVP(verboseCheirality_);

View File

@ -203,7 +203,7 @@ private:
/// Serialization function /// Serialization function
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version) { void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base); ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
ar & BOOST_SERIALIZATION_NVP(K_all_); ar & BOOST_SERIALIZATION_NVP(K_all_);
} }

View File

@ -169,7 +169,7 @@ private:
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class Archive> template<class Archive>
void serialize(Archive & ar, const unsigned int version) { void serialize(Archive & ar, const unsigned int /*version*/) {
ar & boost::serialization::make_nvp("NoiseModelFactor2", ar & boost::serialization::make_nvp("NoiseModelFactor2",
boost::serialization::base_object<Base>(*this)); boost::serialization::base_object<Base>(*this));
ar & BOOST_SERIALIZATION_NVP(measured_); ar & BOOST_SERIALIZATION_NVP(measured_);

View File

@ -184,7 +184,7 @@ private:
/// Serialization function /// Serialization function
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version) { void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base); ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
ar & BOOST_SERIALIZATION_NVP(camera_); ar & BOOST_SERIALIZATION_NVP(camera_);
ar & BOOST_SERIALIZATION_NVP(measured_); ar & BOOST_SERIALIZATION_NVP(measured_);

View File

@ -76,7 +76,7 @@ namespace gtsam {
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version) { void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base); ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
} }
}; };

View File

@ -65,7 +65,7 @@ namespace gtsam {
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version) { void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base); ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
} }
}; };

View File

@ -116,7 +116,7 @@ namespace gtsam {
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class Archive> template<class Archive>
void serialize(Archive & ar, const unsigned int version) { void serialize(Archive & ar, const unsigned int /*version*/) {
ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(BaseFactor); ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(BaseFactor);
ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(BaseConditional); ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(BaseConditional);
} }

View File

@ -144,7 +144,7 @@ namespace gtsam {
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version) { void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base); ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
} }
}; // IndexFactor }; // IndexFactor

View File

@ -111,7 +111,7 @@ namespace gtsam {
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version) { void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base); ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
} }
}; };

View File

@ -182,7 +182,7 @@ private:
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class Archive> template<class Archive>
void serialize(Archive & ar, const unsigned int version) { void serialize(Archive & ar, const unsigned int /*version*/) {
ar & BOOST_SERIALIZATION_NVP(Rt_); ar & BOOST_SERIALIZATION_NVP(Rt_);
ar & BOOST_SERIALIZATION_NVP(v_); ar & BOOST_SERIALIZATION_NVP(v_);
} }

View File

@ -52,7 +52,7 @@ private:
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version) { void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
ar & boost::serialization::make_nvp("NoiseModelFactor3", ar & boost::serialization::make_nvp("NoiseModelFactor3",
boost::serialization::base_object<Base>(*this)); boost::serialization::base_object<Base>(*this));
} }

View File

@ -92,7 +92,7 @@ private:
// Serialization function // Serialization function
friend class boost::serialization::access; friend class boost::serialization::access;
template<class Archive> template<class Archive>
void serialize(Archive & ar, const unsigned int version) { void serialize(Archive & ar, const unsigned int /*version*/) {
ar & BOOST_SERIALIZATION_NVP(azimuth_); ar & BOOST_SERIALIZATION_NVP(azimuth_);
ar & BOOST_SERIALIZATION_NVP(elevation_); ar & BOOST_SERIALIZATION_NVP(elevation_);
} }

View File

@ -175,7 +175,7 @@ private:
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class Archive> template<class Archive>
void serialize(Archive & ar, const unsigned int version) { void serialize(Archive & ar, const unsigned int /*version*/) {
ar & BOOST_SERIALIZATION_NVP(pose_); ar & BOOST_SERIALIZATION_NVP(pose_);
ar & BOOST_SERIALIZATION_NVP(k_); ar & BOOST_SERIALIZATION_NVP(k_);
} }

View File

@ -133,7 +133,7 @@ private:
// Serialization function // Serialization function
friend class boost::serialization::access; friend class boost::serialization::access;
template<class Archive> template<class Archive>
void serialize(Archive & ar, const unsigned int version) { void serialize(Archive & ar, const unsigned int /*version*/) {
ar & BOOST_SERIALIZATION_NVP(T_); ar & BOOST_SERIALIZATION_NVP(T_);
ar & BOOST_SERIALIZATION_NVP(z_); ar & BOOST_SERIALIZATION_NVP(z_);
} }

Some files were not shown because too many files have changed in this diff Show More