Skip to content

Commit

Permalink
Finish 4.2a0
Browse files Browse the repository at this point in the history
  • Loading branch information
dellaert committed Dec 29, 2021
2 parents 69a3a75 + e5b928c commit 811369d
Show file tree
Hide file tree
Showing 197 changed files with 7,008 additions and 1,959 deletions.
25 changes: 17 additions & 8 deletions .github/workflows/build-windows.yml
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,11 @@ jobs:
windows-2019-cl,
]

build_type: [Debug, Release]
build_type: [
Debug,
#TODO(Varun) The release build takes over 2.5 hours, need to figure out why.
# Release
]
build_unstable: [ON]
include:
#TODO This build fails, need to understand why.
Expand Down Expand Up @@ -90,13 +94,18 @@ jobs:
- name: Checkout
uses: actions/checkout@v2

- name: Build
- name: Configuration
run: |
cmake -E remove_directory build
cmake -B build -S . -DGTSAM_BUILD_EXAMPLES_ALWAYS=OFF -DBOOST_ROOT="${env:BOOST_ROOT}" -DBOOST_INCLUDEDIR="${env:BOOST_ROOT}\boost\include" -DBOOST_LIBRARYDIR="${env:BOOST_ROOT}\lib"
cmake --build build --config ${{ matrix.build_type }} --target gtsam
cmake --build build --config ${{ matrix.build_type }} --target gtsam_unstable
cmake --build build --config ${{ matrix.build_type }} --target wrap
cmake --build build --config ${{ matrix.build_type }} --target check.base
cmake --build build --config ${{ matrix.build_type }} --target check.base_unstable
cmake --build build --config ${{ matrix.build_type }} --target check.linear
- name: Build
run: |
# Since Visual Studio is a multi-generator, we need to use --config
# https://stackoverflow.com/a/24470998/1236990
cmake --build build -j 4 --config ${{ matrix.build_type }} --target gtsam
cmake --build build -j 4 --config ${{ matrix.build_type }} --target gtsam_unstable
cmake --build build -j 4 --config ${{ matrix.build_type }} --target wrap
cmake --build build -j 4 --config ${{ matrix.build_type }} --target check.base
cmake --build build -j 4 --config ${{ matrix.build_type }} --target check.base_unstable
cmake --build build -j 4 --config ${{ matrix.build_type }} --target check.linear
21 changes: 17 additions & 4 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -9,12 +9,18 @@ endif()

# Set the version number for the library
set (GTSAM_VERSION_MAJOR 4)
set (GTSAM_VERSION_MINOR 1)
set (GTSAM_VERSION_PATCH 1)
set (GTSAM_VERSION_MINOR 2)
set (GTSAM_VERSION_PATCH 0)
set (GTSAM_PRERELEASE_VERSION "a0")
math (EXPR GTSAM_VERSION_NUMERIC "10000 * ${GTSAM_VERSION_MAJOR} + 100 * ${GTSAM_VERSION_MINOR} + ${GTSAM_VERSION_PATCH}")
set (GTSAM_VERSION_STRING "${GTSAM_VERSION_MAJOR}.${GTSAM_VERSION_MINOR}.${GTSAM_VERSION_PATCH}")

set (CMAKE_PROJECT_VERSION ${GTSAM_VERSION_STRING})
if (${GTSAM_VERSION_PATCH} EQUAL 0)
set (GTSAM_VERSION_STRING "${GTSAM_VERSION_MAJOR}.${GTSAM_VERSION_MINOR}${GTSAM_PRERELEASE_VERSION}")
else()
set (GTSAM_VERSION_STRING "${GTSAM_VERSION_MAJOR}.${GTSAM_VERSION_MINOR}.${GTSAM_VERSION_PATCH}${GTSAM_PRERELEASE_VERSION}")
endif()
message(STATUS "GTSAM Version: ${GTSAM_VERSION_STRING}")

set (CMAKE_PROJECT_VERSION_MAJOR ${GTSAM_VERSION_MAJOR})
set (CMAKE_PROJECT_VERSION_MINOR ${GTSAM_VERSION_MINOR})
set (CMAKE_PROJECT_VERSION_PATCH ${GTSAM_VERSION_PATCH})
Expand Down Expand Up @@ -87,6 +93,13 @@ if(GTSAM_BUILD_PYTHON OR GTSAM_INSTALL_MATLAB_TOOLBOX)
CACHE STRING "The Python version to use for wrapping")
# Set the include directory for matlab.h
set(GTWRAP_INCLUDE_NAME "wrap")

# Copy matlab.h to the correct folder.
configure_file(${PROJECT_SOURCE_DIR}/wrap/matlab.h
${PROJECT_BINARY_DIR}/wrap/matlab.h COPYONLY)
# Add the include directories so that matlab.h can be found
include_directories("${PROJECT_BINARY_DIR}" "${GTSAM_EIGEN_INCLUDE_FOR_BUILD}")

add_subdirectory(wrap)
list(APPEND CMAKE_MODULE_PATH "${CMAKE_CURRENT_LIST_DIR}/wrap/cmake")
endif()
Expand Down
4 changes: 2 additions & 2 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -2,9 +2,9 @@

**Important Note**

As of August 1 2020, the `develop` branch is officially in "Pre 4.1" mode, and features deprecated in 4.0 have been removed. Please use the last [4.0.3 release](https://github.com/borglab/gtsam/releases/tag/4.0.3) if you need those features.
As of Dec 2021, the `develop` branch is officially in "Pre 4.2" mode. A great new feature we will be adding in 4.2 is *hybrid inference* a la DCSLAM (Kevin Doherty et al) and we envision several API-breaking changes will happen in the discrete folder.

However, most are easily converted and can be tracked down (in 4.0.3) by disabling the cmake flag `GTSAM_ALLOW_DEPRECATED_SINCE_V4`.
In addition, features deprecated in 4.1 will be removed. Please use the last [4.1.1 release](https://github.com/borglab/gtsam/releases/tag/4.1.1) if you need those features. However, most (not all, unfortunately) are easily converted and can be tracked down (in 4.1.1) by disabling the cmake flag `GTSAM_ALLOW_DEPRECATED_SINCE_V41`.

## What is GTSAM?

Expand Down
12 changes: 6 additions & 6 deletions examples/DiscreteBayesNetExample.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -56,8 +56,8 @@ int main(int argc, char **argv) {
DiscreteBayesNet::shared_ptr chordal = fg.eliminateSequential(ordering);

// solve
DiscreteFactor::sharedValues mpe = chordal->optimize();
GTSAM_PRINT(*mpe);
auto mpe = chordal->optimize();
GTSAM_PRINT(mpe);

// We can also build a Bayes tree (directed junction tree).
// The elimination order above will do fine:
Expand All @@ -70,14 +70,14 @@ int main(int argc, char **argv) {

// solve again, now with evidence
DiscreteBayesNet::shared_ptr chordal2 = fg.eliminateSequential(ordering);
DiscreteFactor::sharedValues mpe2 = chordal2->optimize();
GTSAM_PRINT(*mpe2);
auto mpe2 = chordal2->optimize();
GTSAM_PRINT(mpe2);

// We can also sample from it
cout << "\n10 samples:" << endl;
for (size_t i = 0; i < 10; i++) {
DiscreteFactor::sharedValues sample = chordal2->sample();
GTSAM_PRINT(*sample);
auto sample = chordal2->sample();
GTSAM_PRINT(sample);
}
return 0;
}
16 changes: 8 additions & 8 deletions examples/DiscreteBayesNet_FG.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -33,11 +33,11 @@ using namespace gtsam;
int main(int argc, char **argv) {
// Define keys and a print function
Key C(1), S(2), R(3), W(4);
auto print = [=](DiscreteFactor::sharedValues values) {
cout << boolalpha << "Cloudy = " << static_cast<bool>((*values)[C])
<< " Sprinkler = " << static_cast<bool>((*values)[S])
<< " Rain = " << boolalpha << static_cast<bool>((*values)[R])
<< " WetGrass = " << static_cast<bool>((*values)[W]) << endl;
auto print = [=](const DiscreteFactor::Values& values) {
cout << boolalpha << "Cloudy = " << static_cast<bool>(values.at(C))
<< " Sprinkler = " << static_cast<bool>(values.at(S))
<< " Rain = " << boolalpha << static_cast<bool>(values.at(R))
<< " WetGrass = " << static_cast<bool>(values.at(W)) << endl;
};

// We assume binary state variables
Expand Down Expand Up @@ -85,7 +85,7 @@ int main(int argc, char **argv) {
}

// "Most Probable Explanation", i.e., configuration with largest value
DiscreteFactor::sharedValues mpe = graph.eliminateSequential()->optimize();
auto mpe = graph.eliminateSequential()->optimize();
cout << "\nMost Probable Explanation (MPE):" << endl;
print(mpe);

Expand All @@ -97,7 +97,7 @@ int main(int argc, char **argv) {

// solve again, now with evidence
DiscreteBayesNet::shared_ptr chordal = graph.eliminateSequential();
DiscreteFactor::sharedValues mpe_with_evidence = chordal->optimize();
auto mpe_with_evidence = chordal->optimize();

cout << "\nMPE given C=0:" << endl;
print(mpe_with_evidence);
Expand All @@ -113,7 +113,7 @@ int main(int argc, char **argv) {
// We can also sample from it
cout << "\n10 samples:" << endl;
for (size_t i = 0; i < 10; i++) {
DiscreteFactor::sharedValues sample = chordal->sample();
auto sample = chordal->sample();
print(sample);
}
return 0;
Expand Down
3 changes: 1 addition & 2 deletions examples/FisheyeExample.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -122,8 +122,7 @@ int main(int argc, char *argv[]) {
std::cout << "initial error=" << graph.error(initialEstimate) << std::endl;
std::cout << "final error=" << graph.error(result) << std::endl;

std::ofstream os("examples/vio_batch.dot");
graph.saveGraph(os, result);
graph.saveGraph("examples/vio_batch.dot", result);

return 0;
}
Expand Down
8 changes: 4 additions & 4 deletions examples/HMMExample.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -66,14 +66,14 @@ int main(int argc, char **argv) {
chordal->print("Eliminated");

// solve
DiscreteFactor::sharedValues mpe = chordal->optimize();
GTSAM_PRINT(*mpe);
auto mpe = chordal->optimize();
GTSAM_PRINT(mpe);

// We can also sample from it
cout << "\n10 samples:" << endl;
for (size_t k = 0; k < 10; k++) {
DiscreteFactor::sharedValues sample = chordal->sample();
GTSAM_PRINT(*sample);
auto sample = chordal->sample();
GTSAM_PRINT(sample);
}

// Or compute the marginals. This re-eliminates the FG into a Bayes tree
Expand Down
5 changes: 2 additions & 3 deletions examples/Pose2SLAMExample_graphviz.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -60,11 +60,10 @@ int main(int argc, char** argv) {

// save factor graph as graphviz dot file
// Render to PDF using "fdp Pose2SLAMExample.dot -Tpdf > graph.pdf"
ofstream os("Pose2SLAMExample.dot");
graph.saveGraph(os, result);
graph.saveGraph("Pose2SLAMExample.dot", result);

// Also print out to console
graph.saveGraph(cout, result);
graph.dot(cout, result);

return 0;
}
4 changes: 2 additions & 2 deletions examples/UGM_chain.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -70,8 +70,8 @@ int main(int argc, char** argv) {
// "Decoding", i.e., configuration with largest value
// We use sequential variable elimination
DiscreteBayesNet::shared_ptr chordal = graph.eliminateSequential();
DiscreteFactor::sharedValues optimalDecoding = chordal->optimize();
optimalDecoding->print("\nMost Probable Explanation (optimalDecoding)\n");
auto optimalDecoding = chordal->optimize();
optimalDecoding.print("\nMost Probable Explanation (optimalDecoding)\n");

// "Inference" Computing marginals for each node
// Here we'll make use of DiscreteMarginals class, which makes use of
Expand Down
4 changes: 2 additions & 2 deletions examples/UGM_small.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -63,8 +63,8 @@ int main(int argc, char** argv) {
// "Decoding", i.e., configuration with largest value (MPE)
// We use sequential variable elimination
DiscreteBayesNet::shared_ptr chordal = graph.eliminateSequential();
DiscreteFactor::sharedValues optimalDecoding = chordal->optimize();
optimalDecoding->print("\noptimalDecoding");
auto optimalDecoding = chordal->optimize();
GTSAM_PRINT(optimalDecoding);

// "Inference" Computing marginals
cout << "\nComputing Node Marginals .." << endl;
Expand Down
2 changes: 1 addition & 1 deletion gtsam/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@ set (gtsam_subdirs
sam
sfm
slam
navigation
navigation
)

set(gtsam_srcs)
Expand Down
2 changes: 1 addition & 1 deletion gtsam/base/base.i
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,7 @@ class DSFMap {
DSFMap();
KEY find(const KEY& key) const;
void merge(const KEY& x, const KEY& y);
std::map<KEY, Set> sets();
std::map<KEY, This::Set> sets();
};

class IndexPairSet {
Expand Down
4 changes: 2 additions & 2 deletions gtsam/base/tests/testMatrix.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -173,7 +173,7 @@ TEST(Matrix, stack )
{
Matrix A = (Matrix(2, 2) << -5.0, 3.0, 00.0, -5.0).finished();
Matrix B = (Matrix(3, 2) << -0.5, 2.1, 1.1, 3.4, 2.6, 7.1).finished();
Matrix AB = stack(2, &A, &B);
Matrix AB = gtsam::stack(2, &A, &B);
Matrix C(5, 2);
for (int i = 0; i < 2; i++)
for (int j = 0; j < 2; j++)
Expand All @@ -187,7 +187,7 @@ TEST(Matrix, stack )
std::vector<gtsam::Matrix> matrices;
matrices.push_back(A);
matrices.push_back(B);
Matrix AB2 = stack(matrices);
Matrix AB2 = gtsam::stack(matrices);
EQUALITY(C,AB2);
}

Expand Down
2 changes: 1 addition & 1 deletion gtsam/basis/basis.i
Original file line number Diff line number Diff line change
Expand Up @@ -140,7 +140,7 @@ class FitBasis {
static gtsam::GaussianFactorGraph::shared_ptr LinearGraph(
const std::map<double, double>& sequence,
const gtsam::noiseModel::Base* model, size_t N);
Parameters parameters() const;
This::Parameters parameters() const;
};

} // namespace gtsam
20 changes: 15 additions & 5 deletions gtsam/discrete/DecisionTree-inl.h
Original file line number Diff line number Diff line change
Expand Up @@ -248,8 +248,9 @@ namespace gtsam {
void dot(std::ostream& os, bool showZero) const override {
os << "\"" << this->id() << "\" [shape=circle, label=\"" << label_
<< "\"]\n";
for (size_t i = 0; i < branches_.size(); i++) {
NodePtr branch = branches_[i];
size_t B = branches_.size();
for (size_t i = 0; i < B; i++) {
const NodePtr& branch = branches_[i];

// Check if zero
if (!showZero) {
Expand All @@ -258,8 +259,10 @@ namespace gtsam {
}

os << "\"" << this->id() << "\" -> \"" << branch->id() << "\"";
if (i == 0) os << " [style=dashed]";
if (i > 1) os << " [style=bold]";
if (B == 2) {
if (i == 0) os << " [style=dashed]";
if (i > 1) os << " [style=bold]";
}
os << std::endl;
branch->dot(os, showZero);
}
Expand Down Expand Up @@ -671,7 +674,14 @@ namespace gtsam {
int result = system(
("dot -Tpdf " + name + ".dot -o " + name + ".pdf >& /dev/null").c_str());
if (result==-1) throw std::runtime_error("DecisionTree::dot system call failed");
}
}

template<typename L, typename Y>
std::string DecisionTree<L, Y>::dot(bool showZero) const {
std::stringstream ss;
dot(ss, showZero);
return ss.str();
}

/*********************************************************************************/

Expand Down
7 changes: 6 additions & 1 deletion gtsam/discrete/DecisionTree.h
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,8 @@

#pragma once

#include <gtsam/base/types.h>

#include <gtsam/discrete/Assignment.h>

#include <boost/function.hpp>
Expand All @@ -35,7 +37,7 @@ namespace gtsam {
* Y = function range (any algebra), e.g., bool, int, double
*/
template<typename L, typename Y>
class DecisionTree {
class GTSAM_EXPORT DecisionTree {

public:

Expand Down Expand Up @@ -198,6 +200,9 @@ namespace gtsam {
/** output to graphviz format, open a file */
void dot(const std::string& name, bool showZero = true) const;

/** output to graphviz format string */
std::string dot(bool showZero = true) const;

/// @name Advanced Interface
/// @{

Expand Down
49 changes: 48 additions & 1 deletion gtsam/discrete/DecisionTreeFactor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -134,5 +134,52 @@ namespace gtsam {
return boost::make_shared<DecisionTreeFactor>(dkeys, result);
}

/* ************************************************************************* */
/* ************************************************************************* */
std::vector<std::pair<DiscreteValues, double>> DecisionTreeFactor::enumerate() const {
// Get all possible assignments
std::vector<std::pair<Key, size_t>> pairs;
for (auto& key : keys()) {
pairs.emplace_back(key, cardinalities_.at(key));
}
// Reverse to make cartesianProduct output a more natural ordering.
std::vector<std::pair<Key, size_t>> rpairs(pairs.rbegin(), pairs.rend());
const auto assignments = cartesianProduct(rpairs);

// Construct unordered_map with values
std::vector<std::pair<DiscreteValues, double>> result;
for (const auto& assignment : assignments) {
result.emplace_back(assignment, operator()(assignment));
}
return result;
}

/* ************************************************************************* */
std::string DecisionTreeFactor::markdown(
const KeyFormatter& keyFormatter) const {
std::stringstream ss;

// Print out header and construct argument for `cartesianProduct`.
ss << "|";
for (auto& key : keys()) {
ss << keyFormatter(key) << "|";
}
ss << "value|\n";

// Print out separator with alignment hints.
ss << "|";
for (size_t j = 0; j < size(); j++) ss << ":-:|";
ss << ":-:|\n";

// Print out all rows.
auto rows = enumerate();
for (const auto& kv : rows) {
ss << "|";
auto assignment = kv.first;
for (auto& key : keys()) ss << assignment.at(key) << "|";
ss << kv.second << "|\n";
}
return ss.str();
}

/* ************************************************************************* */
} // namespace gtsam
Loading

0 comments on commit 811369d

Please sign in to comment.