Skip to content

Commit a74c7dd

Browse files
authored
Merge pull request #1099 from borglab/release/4.2a5
2 parents d6edcea + 46f3a48 commit a74c7dd

File tree

101 files changed

+2540
-1318
lines changed

Some content is hidden

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

101 files changed

+2540
-1318
lines changed

CMakeLists.txt

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -11,7 +11,7 @@ endif()
1111
set (GTSAM_VERSION_MAJOR 4)
1212
set (GTSAM_VERSION_MINOR 2)
1313
set (GTSAM_VERSION_PATCH 0)
14-
set (GTSAM_PRERELEASE_VERSION "a4")
14+
set (GTSAM_PRERELEASE_VERSION "a5")
1515
math (EXPR GTSAM_VERSION_NUMERIC "10000 * ${GTSAM_VERSION_MAJOR} + 100 * ${GTSAM_VERSION_MINOR} + ${GTSAM_VERSION_PATCH}")
1616

1717
if (${GTSAM_VERSION_PATCH} EQUAL 0)

examples/SFMExampleExpressions_bal.cpp

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -28,7 +28,8 @@
2828
// Header order is close to far
2929
#include <gtsam/inference/Symbol.h>
3030
#include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
31-
#include <gtsam/slam/dataset.h> // for loading BAL datasets !
31+
#include <gtsam/sfm/SfmData.h> // for loading BAL datasets !
32+
#include <gtsam/slam/dataset.h>
3233
#include <vector>
3334

3435
using namespace std;
@@ -46,10 +47,9 @@ int main(int argc, char* argv[]) {
4647
if (argc > 1) filename = string(argv[1]);
4748

4849
// Load the SfM data from file
49-
SfmData mydata;
50-
readBAL(filename, mydata);
50+
SfmData mydata = SfmData::FromBalFile(filename);
5151
cout << boost::format("read %1% tracks on %2% cameras\n") %
52-
mydata.number_tracks() % mydata.number_cameras();
52+
mydata.numberTracks() % mydata.numberCameras();
5353

5454
// Create a factor graph
5555
ExpressionFactorGraph graph;

examples/SFMExample_bal.cpp

Lines changed: 5 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -10,7 +10,7 @@
1010
* -------------------------------------------------------------------------- */
1111

1212
/**
13-
* @file SFMExample.cpp
13+
* @file SFMExample_bal.cpp
1414
* @brief Solve a structure-from-motion problem from a "Bundle Adjustment in the Large" file
1515
* @author Frank Dellaert
1616
*/
@@ -20,7 +20,8 @@
2020
#include <gtsam/nonlinear/NonlinearFactorGraph.h>
2121
#include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
2222
#include <gtsam/slam/GeneralSFMFactor.h>
23-
#include <gtsam/slam/dataset.h> // for loading BAL datasets !
23+
#include <gtsam/sfm/SfmData.h> // for loading BAL datasets !
24+
#include <gtsam/slam/dataset.h>
2425
#include <vector>
2526

2627
using namespace std;
@@ -41,9 +42,8 @@ int main (int argc, char* argv[]) {
4142
if (argc>1) filename = string(argv[1]);
4243

4344
// Load the SfM data from file
44-
SfmData mydata;
45-
readBAL(filename, mydata);
46-
cout << boost::format("read %1% tracks on %2% cameras\n") % mydata.number_tracks() % mydata.number_cameras();
45+
SfmData mydata = SfmData::FromBalFile(filename);
46+
cout << boost::format("read %1% tracks on %2% cameras\n") % mydata.numberTracks() % mydata.numberCameras();
4747

4848
// Create a factor graph
4949
NonlinearFactorGraph graph;

examples/SFMExample_bal_COLAMD_METIS.cpp

Lines changed: 5 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -22,7 +22,8 @@
2222
#include <gtsam/nonlinear/NonlinearFactorGraph.h>
2323
#include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
2424
#include <gtsam/slam/GeneralSFMFactor.h>
25-
#include <gtsam/slam/dataset.h> // for loading BAL datasets !
25+
#include <gtsam/sfm/SfmData.h> // for loading BAL datasets !
26+
#include <gtsam/slam/dataset.h>
2627

2728
#include <gtsam/base/timing.h>
2829

@@ -45,10 +46,9 @@ int main(int argc, char* argv[]) {
4546
if (argc > 1) filename = string(argv[1]);
4647

4748
// Load the SfM data from file
48-
SfmData mydata;
49-
readBAL(filename, mydata);
49+
SfmData mydata = SfmData::FromBalFile(filename);
5050
cout << boost::format("read %1% tracks on %2% cameras\n") %
51-
mydata.number_tracks() % mydata.number_cameras();
51+
mydata.numberTracks() % mydata.numberCameras();
5252

5353
// Create a factor graph
5454
NonlinearFactorGraph graph;
@@ -131,7 +131,7 @@ int main(int argc, char* argv[]) {
131131

132132
cout << "Time comparison by solving " << filename << " results:" << endl;
133133
cout << boost::format("%1% point tracks and %2% cameras\n") %
134-
mydata.number_tracks() % mydata.number_cameras()
134+
mydata.numberTracks() % mydata.numberCameras()
135135
<< endl;
136136

137137
tictoc_print_();

gtsam/base/FastSet.h

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -18,6 +18,9 @@
1818

1919
#pragma once
2020

21+
#if BOOST_VERSION >= 107400
22+
#include <boost/serialization/library_version_type.hpp>
23+
#endif
2124
#include <boost/serialization/nvp.hpp>
2225
#include <boost/serialization/set.hpp>
2326
#include <gtsam/base/FastDefaultAllocator.h>

gtsam/base/serialization.h

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -25,6 +25,7 @@
2525
#include <string>
2626

2727
// includes for standard serialization types
28+
#include <boost/serialization/version.hpp>
2829
#include <boost/serialization/optional.hpp>
2930
#include <boost/serialization/shared_ptr.hpp>
3031
#include <boost/serialization/vector.hpp>

gtsam/discrete/DiscreteConditional.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -225,13 +225,13 @@ DecisionTreeFactor::shared_ptr DiscreteConditional::likelihood(
225225

226226
/* ****************************************************************************/
227227
DecisionTreeFactor::shared_ptr DiscreteConditional::likelihood(
228-
size_t parent_value) const {
228+
size_t frontal) const {
229229
if (nrFrontals() != 1)
230230
throw std::invalid_argument(
231231
"Single value likelihood can only be invoked on single-variable "
232232
"conditional");
233233
DiscreteValues values;
234-
values.emplace(keys_[0], parent_value);
234+
values.emplace(keys_[0], frontal);
235235
return likelihood(values);
236236
}
237237

gtsam/discrete/DiscreteConditional.h

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -177,7 +177,7 @@ class GTSAM_EXPORT DiscreteConditional
177177
const DiscreteValues& frontalValues) const;
178178

179179
/** Single variable version of likelihood. */
180-
DecisionTreeFactor::shared_ptr likelihood(size_t parent_value) const;
180+
DecisionTreeFactor::shared_ptr likelihood(size_t frontal) const;
181181

182182
/**
183183
* sample

gtsam/discrete/discrete.i

Lines changed: 11 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -70,7 +70,7 @@ virtual class DecisionTreeFactor : gtsam::DiscreteFactor {
7070
string dot(
7171
const gtsam::KeyFormatter& keyFormatter = gtsam::DefaultKeyFormatter,
7272
bool showZero = true) const;
73-
std::vector<std::pair<DiscreteValues, double>> enumerate() const;
73+
std::vector<std::pair<gtsam::DiscreteValues, double>> enumerate() const;
7474
string markdown(const gtsam::KeyFormatter& keyFormatter =
7575
gtsam::DefaultKeyFormatter) const;
7676
string markdown(const gtsam::KeyFormatter& keyFormatter,
@@ -97,7 +97,7 @@ virtual class DiscreteConditional : gtsam::DecisionTreeFactor {
9797
const gtsam::Ordering& orderedKeys);
9898
gtsam::DiscreteConditional operator*(
9999
const gtsam::DiscreteConditional& other) const;
100-
DiscreteConditional marginal(gtsam::Key key) const;
100+
gtsam::DiscreteConditional marginal(gtsam::Key key) const;
101101
void print(string s = "Discrete Conditional\n",
102102
const gtsam::KeyFormatter& keyFormatter =
103103
gtsam::DefaultKeyFormatter) const;
@@ -269,13 +269,16 @@ class DiscreteFactorGraph {
269269
gtsam::DiscreteLookupDAG maxProduct(gtsam::Ordering::OrderingType type);
270270
gtsam::DiscreteLookupDAG maxProduct(const gtsam::Ordering& ordering);
271271

272-
gtsam::DiscreteBayesNet eliminateSequential();
273-
gtsam::DiscreteBayesNet eliminateSequential(const gtsam::Ordering& ordering);
274-
std::pair<gtsam::DiscreteBayesNet, gtsam::DiscreteFactorGraph>
272+
gtsam::DiscreteBayesNet* eliminateSequential();
273+
gtsam::DiscreteBayesNet* eliminateSequential(gtsam::Ordering::OrderingType type);
274+
gtsam::DiscreteBayesNet* eliminateSequential(const gtsam::Ordering& ordering);
275+
pair<gtsam::DiscreteBayesNet*, gtsam::DiscreteFactorGraph*>
275276
eliminatePartialSequential(const gtsam::Ordering& ordering);
276-
gtsam::DiscreteBayesTree eliminateMultifrontal();
277-
gtsam::DiscreteBayesTree eliminateMultifrontal(const gtsam::Ordering& ordering);
278-
std::pair<gtsam::DiscreteBayesTree, gtsam::DiscreteFactorGraph>
277+
278+
gtsam::DiscreteBayesTree* eliminateMultifrontal();
279+
gtsam::DiscreteBayesTree* eliminateMultifrontal(gtsam::Ordering::OrderingType type);
280+
gtsam::DiscreteBayesTree* eliminateMultifrontal(const gtsam::Ordering& ordering);
281+
pair<gtsam::DiscreteBayesTree*, gtsam::DiscreteFactorGraph*>
279282
eliminatePartialMultifrontal(const gtsam::Ordering& ordering);
280283

281284
string dot(

gtsam/discrete/tests/testDiscreteBayesNet.cpp

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -150,7 +150,6 @@ TEST(DiscreteBayesNet, Dot) {
150150
fragment.add((Either | Tuberculosis, LungCancer) = "F T T T");
151151

152152
string actual = fragment.dot();
153-
cout << actual << endl;
154153
EXPECT(actual ==
155154
"digraph {\n"
156155
" size=\"5,5\";\n"

0 commit comments

Comments
 (0)