Skip to content

Commit df5b894

Browse files
authored
Merge pull request #1344 from borglab/feature/NoiseModelFactorN_replaceDeprecated
2 parents 1ab922b + a3e314f commit df5b894

File tree

83 files changed

+498
-384
lines changed

Some content is hidden

Large Commits have some content hidden by default. Use the searchbox below for content that may be hidden.

83 files changed

+498
-384
lines changed

examples/CameraResectioning.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -30,8 +30,8 @@ using symbol_shorthand::X;
3030
* Unary factor on the unknown pose, resulting from meauring the projection of
3131
* a known 3D point in the image
3232
*/
33-
class ResectioningFactor: public NoiseModelFactor1<Pose3> {
34-
typedef NoiseModelFactor1<Pose3> Base;
33+
class ResectioningFactor: public NoiseModelFactorN<Pose3> {
34+
typedef NoiseModelFactorN<Pose3> Base;
3535

3636
Cal3_S2::shared_ptr K_; ///< camera's intrinsic parameters
3737
Point3 P_; ///< 3D point on the calibration rig

examples/LocalizationExample.cpp

+4-4
Original file line numberDiff line numberDiff line change
@@ -62,10 +62,10 @@ using namespace gtsam;
6262
//
6363
// The factor will be a unary factor, affect only a single system variable. It will
6464
// also use a standard Gaussian noise model. Hence, we will derive our new factor from
65-
// the NoiseModelFactor1.
65+
// the NoiseModelFactorN.
6666
#include <gtsam/nonlinear/NonlinearFactor.h>
6767

68-
class UnaryFactor: public NoiseModelFactor1<Pose2> {
68+
class UnaryFactor: public NoiseModelFactorN<Pose2> {
6969
// The factor will hold a measurement consisting of an (X,Y) location
7070
// We could this with a Point2 but here we just use two doubles
7171
double mx_, my_;
@@ -76,11 +76,11 @@ class UnaryFactor: public NoiseModelFactor1<Pose2> {
7676

7777
// The constructor requires the variable key, the (X, Y) measurement value, and the noise model
7878
UnaryFactor(Key j, double x, double y, const SharedNoiseModel& model):
79-
NoiseModelFactor1<Pose2>(model, j), mx_(x), my_(y) {}
79+
NoiseModelFactorN<Pose2>(model, j), mx_(x), my_(y) {}
8080

8181
~UnaryFactor() override {}
8282

83-
// Using the NoiseModelFactor1 base class there are two functions that must be overridden.
83+
// Using the NoiseModelFactorN base class there are two functions that must be overridden.
8484
// The first is the 'evaluateError' function. This function implements the desired measurement
8585
// function, returning a vector of errors when evaluated at the provided variable value. It
8686
// must also calculate the Jacobians for this measurement function, if requested.

examples/Pose3SLAMExample_changeKeys.cpp

+4-4
Original file line numberDiff line numberDiff line change
@@ -71,11 +71,11 @@ int main(const int argc, const char *argv[]) {
7171
if (pose3Between){
7272
Key key1, key2;
7373
if(add){
74-
key1 = pose3Between->key1() + firstKey;
75-
key2 = pose3Between->key2() + firstKey;
74+
key1 = pose3Between->key<1>() + firstKey;
75+
key2 = pose3Between->key<2>() + firstKey;
7676
}else{
77-
key1 = pose3Between->key1() - firstKey;
78-
key2 = pose3Between->key2() - firstKey;
77+
key1 = pose3Between->key<1>() - firstKey;
78+
key2 = pose3Between->key<2>() - firstKey;
7979
}
8080
NonlinearFactor::shared_ptr simpleFactor(
8181
new BetweenFactor<Pose3>(key1, key2, pose3Between->measured(), pose3Between->noiseModel()));

examples/SolverComparer.cpp

+14-14
Original file line numberDiff line numberDiff line change
@@ -69,8 +69,8 @@ namespace br = boost::range;
6969

7070
typedef Pose2 Pose;
7171

72-
typedef NoiseModelFactor1<Pose> NM1;
73-
typedef NoiseModelFactor2<Pose,Pose> NM2;
72+
typedef NoiseModelFactorN<Pose> NM1;
73+
typedef NoiseModelFactorN<Pose,Pose> NM2;
7474
typedef BearingRangeFactor<Pose,Point2> BR;
7575

7676
double chi2_red(const gtsam::NonlinearFactorGraph& graph, const gtsam::Values& config) {
@@ -261,7 +261,7 @@ void runIncremental()
261261
if(BetweenFactor<Pose>::shared_ptr factor =
262262
boost::dynamic_pointer_cast<BetweenFactor<Pose> >(datasetMeasurements[nextMeasurement]))
263263
{
264-
Key key1 = factor->key1(), key2 = factor->key2();
264+
Key key1 = factor->key<1>(), key2 = factor->key<2>();
265265
if(((int)key1 >= firstStep && key1 < key2) || ((int)key2 >= firstStep && key2 < key1)) {
266266
// We found an odometry starting at firstStep
267267
firstPose = std::min(key1, key2);
@@ -313,34 +313,34 @@ void runIncremental()
313313
boost::dynamic_pointer_cast<BetweenFactor<Pose> >(measurementf))
314314
{
315315
// Stop collecting measurements that are for future steps
316-
if(factor->key1() > step || factor->key2() > step)
316+
if(factor->key<1>() > step || factor->key<2>() > step)
317317
break;
318318

319319
// Require that one of the nodes is the current one
320-
if(factor->key1() != step && factor->key2() != step)
320+
if(factor->key<1>() != step && factor->key<2>() != step)
321321
throw runtime_error("Problem in data file, out-of-sequence measurements");
322322

323323
// Add a new factor
324324
newFactors.push_back(factor);
325325
const auto& measured = factor->measured();
326326

327327
// Initialize the new variable
328-
if(factor->key1() > factor->key2()) {
329-
if(!newVariables.exists(factor->key1())) { // Only need to check newVariables since loop closures come after odometry
328+
if(factor->key<1>() > factor->key<2>()) {
329+
if(!newVariables.exists(factor->key<1>())) { // Only need to check newVariables since loop closures come after odometry
330330
if(step == 1)
331-
newVariables.insert(factor->key1(), measured.inverse());
331+
newVariables.insert(factor->key<1>(), measured.inverse());
332332
else {
333-
Pose prevPose = isam2.calculateEstimate<Pose>(factor->key2());
334-
newVariables.insert(factor->key1(), prevPose * measured.inverse());
333+
Pose prevPose = isam2.calculateEstimate<Pose>(factor->key<2>());
334+
newVariables.insert(factor->key<1>(), prevPose * measured.inverse());
335335
}
336336
}
337337
} else {
338-
if(!newVariables.exists(factor->key2())) { // Only need to check newVariables since loop closures come after odometry
338+
if(!newVariables.exists(factor->key<2>())) { // Only need to check newVariables since loop closures come after odometry
339339
if(step == 1)
340-
newVariables.insert(factor->key2(), measured);
340+
newVariables.insert(factor->key<2>(), measured);
341341
else {
342-
Pose prevPose = isam2.calculateEstimate<Pose>(factor->key1());
343-
newVariables.insert(factor->key2(), prevPose * measured);
342+
Pose prevPose = isam2.calculateEstimate<Pose>(factor->key<1>());
343+
newVariables.insert(factor->key<2>(), prevPose * measured);
344344
}
345345
}
346346
}

gtsam/base/Testable.h

+1-1
Original file line numberDiff line numberDiff line change
@@ -23,7 +23,7 @@
2323
* void print(const std::string& name) const = 0;
2424
*
2525
* equality up to tolerance
26-
* tricky to implement, see NoiseModelFactor1 for an example
26+
* tricky to implement, see PriorFactor for an example
2727
* equals is not supposed to print out *anything*, just return true|false
2828
* bool equals(const Derived& expected, double tol) const = 0;
2929
*

gtsam/base/types.h

+35-4
Original file line numberDiff line numberDiff line change
@@ -46,18 +46,49 @@
4646
#include <omp.h>
4747
#endif
4848

49+
/* Define macros for ignoring compiler warnings.
50+
* Usage Example:
51+
* ```
52+
* CLANG_DIAGNOSTIC_PUSH_IGNORE("-Wdeprecated-declarations")
53+
* GCC_DIAGNOSTIC_PUSH_IGNORE("-Wdeprecated-declarations")
54+
* MSVC_DIAGNOSTIC_PUSH_IGNORE(4996)
55+
* // ... code you want to suppress deprecation warnings for ...
56+
* DIAGNOSTIC_POP()
57+
* ```
58+
*/
59+
#define DO_PRAGMA(x) _Pragma (#x)
4960
#ifdef __clang__
5061
# define CLANG_DIAGNOSTIC_PUSH_IGNORE(diag) \
5162
_Pragma("clang diagnostic push") \
52-
_Pragma("clang diagnostic ignored \"" diag "\"")
63+
DO_PRAGMA(clang diagnostic ignored diag)
5364
#else
5465
# define CLANG_DIAGNOSTIC_PUSH_IGNORE(diag)
5566
#endif
5667

57-
#ifdef __clang__
58-
# define CLANG_DIAGNOSTIC_POP() _Pragma("clang diagnostic pop")
68+
#ifdef __GNUC__
69+
# define GCC_DIAGNOSTIC_PUSH_IGNORE(diag) \
70+
_Pragma("GCC diagnostic push") \
71+
DO_PRAGMA(GCC diagnostic ignored diag)
72+
#else
73+
# define GCC_DIAGNOSTIC_PUSH_IGNORE(diag)
74+
#endif
75+
76+
#ifdef _MSC_VER
77+
# define MSVC_DIAGNOSTIC_PUSH_IGNORE(code) \
78+
_Pragma("warning ( push )") \
79+
DO_PRAGMA(warning ( disable : code ))
80+
#else
81+
# define MSVC_DIAGNOSTIC_PUSH_IGNORE(code)
82+
#endif
83+
84+
#if defined(__clang__)
85+
# define DIAGNOSTIC_POP() _Pragma("clang diagnostic pop")
86+
#elif defined(__GNUC__)
87+
# define DIAGNOSTIC_POP() _Pragma("GCC diagnostic pop")
88+
#elif defined(_MSC_VER)
89+
# define DIAGNOSTIC_POP() _Pragma("warning ( pop )")
5990
#else
60-
# define CLANG_DIAGNOSTIC_POP()
91+
# define DIAGNOSTIC_POP()
6192
#endif
6293

6394
namespace gtsam {

gtsam/inference/graph-inl.h

+4-4
Original file line numberDiff line numberDiff line change
@@ -200,8 +200,8 @@ boost::shared_ptr<Values> composePoses(const G& graph, const PredecessorMap<KEY>
200200
boost::shared_ptr<Factor> factor = boost::dynamic_pointer_cast<Factor>(nl_factor);
201201
if (!factor) continue;
202202

203-
KEY key1 = factor->key1();
204-
KEY key2 = factor->key2();
203+
KEY key1 = factor->template key<1>();
204+
KEY key2 = factor->template key<2>();
205205

206206
PoseVertex v1 = key2vertex.find(key1)->second;
207207
PoseVertex v2 = key2vertex.find(key2)->second;
@@ -270,8 +270,8 @@ void split(const G& g, const PredecessorMap<KEY>& tree, G& Ab1, G& Ab2) {
270270
FACTOR2>(factor);
271271
if (!factor2) continue;
272272

273-
KEY key1 = factor2->key1();
274-
KEY key2 = factor2->key2();
273+
KEY key1 = factor2->template key<1>();
274+
KEY key2 = factor2->template key<2>();
275275
// if the tree contains the key
276276
if ((tree.find(key1) != tree.end() &&
277277
tree.find(key1)->second.compare(key2) == 0) ||

gtsam/navigation/AHRSFactor.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -105,8 +105,8 @@ gtsam::NonlinearFactor::shared_ptr AHRSFactor::clone() const {
105105
//------------------------------------------------------------------------------
106106
void AHRSFactor::print(const string& s,
107107
const KeyFormatter& keyFormatter) const {
108-
cout << s << "AHRSFactor(" << keyFormatter(this->key1()) << ","
109-
<< keyFormatter(this->key2()) << "," << keyFormatter(this->key3()) << ",";
108+
cout << s << "AHRSFactor(" << keyFormatter(this->key<1>()) << ","
109+
<< keyFormatter(this->key<2>()) << "," << keyFormatter(this->key<3>()) << ",";
110110
_PIM_.print(" preintegrated measurements:");
111111
noiseModel_->print(" noise model: ");
112112
}

gtsam/navigation/AHRSFactor.h

+3-2
Original file line numberDiff line numberDiff line change
@@ -128,10 +128,10 @@ class GTSAM_EXPORT PreintegratedAhrsMeasurements : public PreintegratedRotation
128128
}
129129
};
130130

131-
class GTSAM_EXPORT AHRSFactor: public NoiseModelFactor3<Rot3, Rot3, Vector3> {
131+
class GTSAM_EXPORT AHRSFactor: public NoiseModelFactorN<Rot3, Rot3, Vector3> {
132132

133133
typedef AHRSFactor This;
134-
typedef NoiseModelFactor3<Rot3, Rot3, Vector3> Base;
134+
typedef NoiseModelFactorN<Rot3, Rot3, Vector3> Base;
135135

136136
PreintegratedAhrsMeasurements _PIM_;
137137

@@ -212,6 +212,7 @@ class GTSAM_EXPORT AHRSFactor: public NoiseModelFactor3<Rot3, Rot3, Vector3> {
212212
friend class boost::serialization::access;
213213
template<class ARCHIVE>
214214
void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
215+
// NoiseModelFactor3 instead of NoiseModelFactorN for backward compatibility
215216
ar
216217
& boost::serialization::make_nvp("NoiseModelFactor3",
217218
boost::serialization::base_object<Base>(*this));

gtsam/navigation/AttitudeFactor.h

+6-4
Original file line numberDiff line numberDiff line change
@@ -76,9 +76,9 @@ class AttitudeFactor {
7676
* Version of AttitudeFactor for Rot3
7777
* @ingroup navigation
7878
*/
79-
class GTSAM_EXPORT Rot3AttitudeFactor: public NoiseModelFactor1<Rot3>, public AttitudeFactor {
79+
class GTSAM_EXPORT Rot3AttitudeFactor: public NoiseModelFactorN<Rot3>, public AttitudeFactor {
8080

81-
typedef NoiseModelFactor1<Rot3> Base;
81+
typedef NoiseModelFactorN<Rot3> Base;
8282

8383
public:
8484

@@ -132,6 +132,7 @@ class GTSAM_EXPORT Rot3AttitudeFactor: public NoiseModelFactor1<Rot3>, public At
132132
friend class boost::serialization::access;
133133
template<class ARCHIVE>
134134
void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
135+
// NoiseModelFactor1 instead of NoiseModelFactorN for backward compatibility
135136
ar & boost::serialization::make_nvp("NoiseModelFactor1",
136137
boost::serialization::base_object<Base>(*this));
137138
ar & boost::serialization::make_nvp("AttitudeFactor",
@@ -149,10 +150,10 @@ template<> struct traits<Rot3AttitudeFactor> : public Testable<Rot3AttitudeFacto
149150
* Version of AttitudeFactor for Pose3
150151
* @ingroup navigation
151152
*/
152-
class GTSAM_EXPORT Pose3AttitudeFactor: public NoiseModelFactor1<Pose3>,
153+
class GTSAM_EXPORT Pose3AttitudeFactor: public NoiseModelFactorN<Pose3>,
153154
public AttitudeFactor {
154155

155-
typedef NoiseModelFactor1<Pose3> Base;
156+
typedef NoiseModelFactorN<Pose3> Base;
156157

157158
public:
158159

@@ -212,6 +213,7 @@ class GTSAM_EXPORT Pose3AttitudeFactor: public NoiseModelFactor1<Pose3>,
212213
friend class boost::serialization::access;
213214
template<class ARCHIVE>
214215
void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
216+
// NoiseModelFactor1 instead of NoiseModelFactorN for backward compatibility
215217
ar & boost::serialization::make_nvp("NoiseModelFactor1",
216218
boost::serialization::base_object<Base>(*this));
217219
ar & boost::serialization::make_nvp("AttitudeFactor",

gtsam/navigation/BarometricFactor.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -26,8 +26,8 @@ namespace gtsam {
2626
void BarometricFactor::print(const string& s,
2727
const KeyFormatter& keyFormatter) const {
2828
cout << (s.empty() ? "" : s + " ") << "Barometric Factor on "
29-
<< keyFormatter(key1()) << "Barometric Bias on "
30-
<< keyFormatter(key2()) << "\n";
29+
<< keyFormatter(key<1>()) << "Barometric Bias on "
30+
<< keyFormatter(key<2>()) << "\n";
3131

3232
cout << " Baro measurement: " << nT_ << "\n";
3333
noiseModel_->print(" noise model: ");

gtsam/navigation/BarometricFactor.h

+3-2
Original file line numberDiff line numberDiff line change
@@ -31,9 +31,9 @@ namespace gtsam {
3131
* https://www.grc.nasa.gov/www/k-12/airplane/atmosmet.html
3232
* @ingroup navigation
3333
*/
34-
class GTSAM_EXPORT BarometricFactor : public NoiseModelFactor2<Pose3, double> {
34+
class GTSAM_EXPORT BarometricFactor : public NoiseModelFactorN<Pose3, double> {
3535
private:
36-
typedef NoiseModelFactor2<Pose3, double> Base;
36+
typedef NoiseModelFactorN<Pose3, double> Base;
3737

3838
double nT_; ///< Height Measurement based on a standard atmosphere
3939

@@ -99,6 +99,7 @@ class GTSAM_EXPORT BarometricFactor : public NoiseModelFactor2<Pose3, double> {
9999
friend class boost::serialization::access;
100100
template <class ARCHIVE>
101101
void serialize(ARCHIVE& ar, const unsigned int /*version*/) {
102+
// NoiseModelFactor1 instead of NoiseModelFactorN for backward compatibility
102103
ar& boost::serialization::make_nvp(
103104
"NoiseModelFactor1",
104105
boost::serialization::base_object<Base>(*this));

gtsam/navigation/CombinedImuFactor.cpp

+3-3
Original file line numberDiff line numberDiff line change
@@ -204,9 +204,9 @@ gtsam::NonlinearFactor::shared_ptr CombinedImuFactor::clone() const {
204204
void CombinedImuFactor::print(const string& s,
205205
const KeyFormatter& keyFormatter) const {
206206
cout << (s.empty() ? s : s + "\n") << "CombinedImuFactor("
207-
<< keyFormatter(this->key1()) << "," << keyFormatter(this->key2()) << ","
208-
<< keyFormatter(this->key3()) << "," << keyFormatter(this->key4()) << ","
209-
<< keyFormatter(this->key5()) << "," << keyFormatter(this->key6())
207+
<< keyFormatter(this->key<1>()) << "," << keyFormatter(this->key<2>()) << ","
208+
<< keyFormatter(this->key<3>()) << "," << keyFormatter(this->key<4>()) << ","
209+
<< keyFormatter(this->key<5>()) << "," << keyFormatter(this->key<6>())
210210
<< ")\n";
211211
_PIM_.print(" preintegrated measurements:");
212212
this->noiseModel_->print(" noise model: ");

gtsam/navigation/CombinedImuFactor.h

+5-3
Original file line numberDiff line numberDiff line change
@@ -255,14 +255,14 @@ class GTSAM_EXPORT PreintegratedCombinedMeasurements : public PreintegrationType
255255
*
256256
* @ingroup navigation
257257
*/
258-
class GTSAM_EXPORT CombinedImuFactor: public NoiseModelFactor6<Pose3, Vector3, Pose3,
258+
class GTSAM_EXPORT CombinedImuFactor: public NoiseModelFactorN<Pose3, Vector3, Pose3,
259259
Vector3, imuBias::ConstantBias, imuBias::ConstantBias> {
260260
public:
261261

262262
private:
263263

264264
typedef CombinedImuFactor This;
265-
typedef NoiseModelFactor6<Pose3, Vector3, Pose3, Vector3,
265+
typedef NoiseModelFactorN<Pose3, Vector3, Pose3, Vector3,
266266
imuBias::ConstantBias, imuBias::ConstantBias> Base;
267267

268268
PreintegratedCombinedMeasurements _PIM_;
@@ -334,7 +334,9 @@ class GTSAM_EXPORT CombinedImuFactor: public NoiseModelFactor6<Pose3, Vector3, P
334334
friend class boost::serialization::access;
335335
template <class ARCHIVE>
336336
void serialize(ARCHIVE& ar, const unsigned int /*version*/) {
337-
ar& BOOST_SERIALIZATION_BASE_OBJECT_NVP(NoiseModelFactor6);
337+
// NoiseModelFactor6 instead of NoiseModelFactorN for backward compatibility
338+
ar& boost::serialization::make_nvp(
339+
"NoiseModelFactor6", boost::serialization::base_object<Base>(*this));
338340
ar& BOOST_SERIALIZATION_NVP(_PIM_);
339341
}
340342

gtsam/navigation/ConstantVelocityFactor.h

+3-3
Original file line numberDiff line numberDiff line change
@@ -26,15 +26,15 @@ namespace gtsam {
2626
* Binary factor for applying a constant velocity model to a moving body represented as a NavState.
2727
* The only measurement is dt, the time delta between the states.
2828
*/
29-
class ConstantVelocityFactor : public NoiseModelFactor2<NavState, NavState> {
29+
class ConstantVelocityFactor : public NoiseModelFactorN<NavState, NavState> {
3030
double dt_;
3131

3232
public:
33-
using Base = NoiseModelFactor2<NavState, NavState>;
33+
using Base = NoiseModelFactorN<NavState, NavState>;
3434

3535
public:
3636
ConstantVelocityFactor(Key i, Key j, double dt, const SharedNoiseModel &model)
37-
: NoiseModelFactor2<NavState, NavState>(model, i, j), dt_(dt) {}
37+
: NoiseModelFactorN<NavState, NavState>(model, i, j), dt_(dt) {}
3838
~ConstantVelocityFactor() override{};
3939

4040
/**

0 commit comments

Comments
 (0)