diff --git a/CMakeLists.txt b/CMakeLists.txt index c315dec..0356e48 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -3,6 +3,7 @@ project(dcsam) # Set some compilation options. set(CMAKE_CXX_STANDARD 17) +set(CMAKE_CXX_STANDARD_REQUIRED ON) if (NOT CMAKE_BUILD_TYPE) # Options: Debug, Release, MinSizeRel, RelWithDebInfo message(STATUS "No build type selected, default to Release") @@ -10,11 +11,11 @@ if (NOT CMAKE_BUILD_TYPE) endif() # Add option to enable testing -option(DCSAM_ENABLE_TESTS "Enable tests" OFF) +option(DCSAM_ENABLE_TESTS "Enable tests" ON) # External package dependencies. -find_package(GTSAM 4.2 REQUIRED) -find_package(Eigen3 3.3 REQUIRED) +find_package(GTSAM REQUIRED) +# We use Eigen bundled with GTSAM, so we don't need to find it separately. # add_definitions(-march=native) # add_definitions(-std=c++1z) @@ -22,7 +23,7 @@ find_package(Eigen3 3.3 REQUIRED) add_library(dcsam SHARED) target_sources(dcsam PRIVATE src/DCSAM.cpp src/HybridFactorGraph.cpp) target_include_directories(dcsam PUBLIC include) -target_link_libraries(dcsam PUBLIC Eigen3::Eigen gtsam) +target_link_libraries(dcsam PUBLIC gtsam) target_compile_options(dcsam PRIVATE -Wall -Wpedantic -Wextra) # Make library accessible to other cmake projects diff --git a/README.md b/README.md index a1d0bf7..b0ba972 100644 --- a/README.md +++ b/README.md @@ -5,11 +5,16 @@ This library, built using GTSAM, provides factor type definitions and a new solver to perform approximate inference on discrete-continuous (hybrid) factor graph models typically encountered in robotics applications. -**NOTE: As of 1/30/2023 the latest version of DC-SAM on `main` depends on GTSAM release 4.2a8.** If you are using GTSAM 4.1.1, check out our [pre-4.2 release tag](https://github.com/MarineRoboticsGroup/dcsam/releases/tag/pre-4.2). This is the version of DC-SAM you would have used if you cloned the repository prior to 1/30/2023. Many thanks to [Parker Lusk](https://github.com/plusk01) for bringing us into the future. +**NOTE: As of 3/01/2026 the latest version of DC-SAM on `main` depends on GTSAM `develop`** -### References +Thanks to [Varun Agrawal](https://github.com/varunagrawal) for bringing DC-SAM up to date with GTSAM. + +If you are using GTSAM 4.1.1, check out our [pre-4.2 release tag](https://github.com/MarineRoboticsGroup/dcsam/releases/tag/pre-4.2). This is the version of DC-SAM you would have used if you cloned the repository prior to 1/30/2023. Many thanks to [Parker Lusk](https://github.com/plusk01) for bringing us into the future. + +## References A technical report describing this library and our solver can be found [here](https://arxiv.org/abs/2204.11936). If you found this code useful, please cite it as: + ```bibtex @article{doherty2022discrete, author={Doherty, Kevin J. and Lu, Ziqi and Singh, Kurran and Leonard, John J.}, @@ -25,16 +30,17 @@ A technical report describing this library and our solver can be found [here](ht ## Prerequisites -- [GTSAM](https://github.com/borglab/gtsam) @ `4.2a8` +- [GTSAM](https://github.com/borglab/gtsam) @ `develop` To retrieve the appropriate version of GTSAM: + ```sh ~ $ git clone https://github.com/borglab/gtsam ~ $ cd gtsam ~/gtsam $ git checkout 4.2a8 ``` -Follow instructions in the GTSAM repository to build and install with your desired configuration. +Follow instructions in the GTSAM repository to build and install with your desired configuration. ### Optional @@ -56,6 +62,7 @@ To build using `cmake`: ### Run tests To run unit tests, first build with testing enabled: + ```bash ~/dcsam $ mkdir build ~/dcsam $ cd build @@ -76,13 +83,17 @@ For example usage, check out [the DC-SAM examples repo](https://github.com/Marin ## Developing We're using [pre-commit](https://pre-commit.com/) for automatic linting. To install `pre-commit` run: -``` + +```sh pip3 install pre-commit ``` + You can verify your installation went through by running `pre-commit --version` and you should see something like `pre-commit 2.7.1`. To get started using `pre-commit` with this codebase, from the project repo run: -``` + +```sh pre-commit install ``` + Now, each time you `git add` new files and try to `git commit` your code will automatically be run through a variety of linters. You won't be able to commit anything until the linters are happy with your code. diff --git a/include/dcsam/DCContinuousFactor.h b/include/dcsam/DCContinuousFactor.h index 1b2d0d2..9a8272e 100644 --- a/include/dcsam/DCContinuousFactor.h +++ b/include/dcsam/DCContinuousFactor.h @@ -40,7 +40,7 @@ namespace dcsam { class DCContinuousFactor : public gtsam::NonlinearFactor { private: gtsam::DiscreteKeys discreteKeys_; - boost::shared_ptr dcfactor_; + std::shared_ptr dcfactor_; DiscreteValues discreteVals_; public: @@ -48,7 +48,7 @@ class DCContinuousFactor : public gtsam::NonlinearFactor { DCContinuousFactor() = default; - explicit DCContinuousFactor(boost::shared_ptr dcfactor) + explicit DCContinuousFactor(std::shared_ptr dcfactor) : discreteKeys_(dcfactor->discreteKeys()), dcfactor_(dcfactor) { keys_ = dcfactor->keys(); } @@ -58,7 +58,7 @@ class DCContinuousFactor : public gtsam::NonlinearFactor { return dcfactor_->error(continuousVals, discreteVals_); } - boost::shared_ptr linearize( + std::shared_ptr linearize( const gtsam::Values& continuousVals) const override { assert(allInitialized()); return dcfactor_->linearize(continuousVals, discreteVals_); diff --git a/include/dcsam/DCDiscreteFactor.h b/include/dcsam/DCDiscreteFactor.h index cbc5723..c6a0b93 100644 --- a/include/dcsam/DCDiscreteFactor.h +++ b/include/dcsam/DCDiscreteFactor.h @@ -42,7 +42,7 @@ class DCDiscreteFactor : public gtsam::DiscreteFactor { private: gtsam::DiscreteKeys discreteKeys_; gtsam::KeyVector continuousKeys_; - boost::shared_ptr dcfactor_; + std::shared_ptr dcfactor_; gtsam::Values continuousVals_; DiscreteValues discreteVals_; @@ -52,7 +52,7 @@ class DCDiscreteFactor : public gtsam::DiscreteFactor { DCDiscreteFactor() = default; DCDiscreteFactor(const gtsam::DiscreteKeys& discreteKeys, - boost::shared_ptr dcfactor) + std::shared_ptr dcfactor) : discreteKeys_(discreteKeys), continuousKeys_(dcfactor->keys()), dcfactor_(dcfactor) { @@ -61,7 +61,7 @@ class DCDiscreteFactor : public gtsam::DiscreteFactor { for (const gtsam::DiscreteKey& k : discreteKeys_) keys_.push_back(k.first); } - explicit DCDiscreteFactor(boost::shared_ptr dcfactor) + explicit DCDiscreteFactor(std::shared_ptr dcfactor) : discreteKeys_(dcfactor->discreteKeys()), continuousKeys_(dcfactor->keys()), dcfactor_(dcfactor) { @@ -82,7 +82,7 @@ class DCDiscreteFactor : public gtsam::DiscreteFactor { virtual ~DCDiscreteFactor() = default; - bool equals(const DiscreteFactor& other, double tol = 1e-9) const override { + bool equals(const DiscreteFactor& other, [[maybe_unused]] double tol = 1e-9) const override { if (!dynamic_cast(&other)) return false; const DCDiscreteFactor& f(static_cast(other)); return (dcfactor_->equals(*f.dcfactor_) && @@ -102,11 +102,79 @@ class DCDiscreteFactor : public gtsam::DiscreteFactor { return dcfactor_->conditionalTimes(f, continuousVals_, discreteVals_); } - double operator()(const DiscreteValues& values) const override { + virtual DiscreteFactor::shared_ptr operator*(double s) const override { + return toDecisionTreeFactor() * s; + } + + double operator()(const DiscreteValues& values) const { assert(allInitialized()); return exp(-dcfactor_->error(continuousVals_, values)); } + void print(const std::string& s = "DCDiscreteFactor:\n", + const gtsam::KeyFormatter& formatter = + gtsam::DefaultKeyFormatter) const override { + toDecisionTreeFactor().print(s, formatter); + continuousVals_.print("Continuous values: ", formatter); + discreteVals_.print("Discrete values: ", formatter); + } + + double evaluate(const gtsam::Assignment& values) const override { + return this->operator()(DiscreteValues(values)); + } + + virtual DiscreteFactor::shared_ptr multiply( + const DiscreteFactor::shared_ptr& df) const override { + return toDecisionTreeFactor().multiply(df); + } + + /// divide by DiscreteFactor::shared_ptr f (safely) + virtual DiscreteFactor::shared_ptr operator/( + const DiscreteFactor::shared_ptr& df) const override { + throw toDecisionTreeFactor() / df; + } + + /// Create new factor by summing all values with the same separator values + virtual DiscreteFactor::shared_ptr sum(size_t nrFrontals) const override { + return toDecisionTreeFactor().sum(nrFrontals); + } + + /// Create new factor by summing all values with the same separator values + virtual DiscreteFactor::shared_ptr sum( + const gtsam::Ordering& keys) const override { + return toDecisionTreeFactor().sum(keys); + } + + /// Find the maximum value in the factor. + virtual double max() const override { + return toDecisionTreeFactor().max(); + } + + /// Create new factor by maximizing over all values with the same separator. + virtual DiscreteFactor::shared_ptr max(size_t nrFrontals) const override { + return toDecisionTreeFactor().max(nrFrontals); + } + + /// Create new factor by maximizing over all values with the same separator. + virtual DiscreteFactor::shared_ptr max( + const gtsam::Ordering& keys) const override { + return toDecisionTreeFactor().max(keys); + } + + /** + * Get the number of non-zero values contained in this factor. + * It could be much smaller than `prod_{key}(cardinality(key))`. + */ + virtual uint64_t nrValues() const override { + return toDecisionTreeFactor().nrValues(); + } + + /// Restrict the factor to the given assignment. + virtual DiscreteFactor::shared_ptr restrict( + const DiscreteValues& assignment) const override { + return toDecisionTreeFactor().restrict(assignment); + } + void updateContinuous(const gtsam::Values& continuousVals) { for (const gtsam::Key& k : continuousKeys_) { // If key `k` is not set continuousVals, skip it. diff --git a/include/dcsam/DCEMFactor.h b/include/dcsam/DCEMFactor.h index 5adace6..485e3ec 100644 --- a/include/dcsam/DCEMFactor.h +++ b/include/dcsam/DCEMFactor.h @@ -150,10 +150,10 @@ class DCEMFactor : public DCFactor { /* * Jacobian magic */ - boost::shared_ptr linearize( + std::shared_ptr linearize( const gtsam::Values& continuousVals, const DiscreteValues& discreteVals) const override { - std::vector> gfs; + std::vector> gfs; // Start by computing all errors, so we can get the component weights. std::vector errors = @@ -169,7 +169,7 @@ class DCEMFactor : public DCFactor { for (size_t i = 0; i < factors_.size(); i++) { // std::cout << "i = " << i << std::endl; // First get the GaussianFactor obtained by linearizing `factors_[i]` - boost::shared_ptr gf = + std::shared_ptr gf = factors_[i].linearize(continuousVals, discreteVals); gtsam::JacobianFactor jf_component(*gf); @@ -197,7 +197,7 @@ class DCEMFactor : public DCFactor { // Stack Jacobians to build combined factor. - return boost::make_shared(gfg); + return std::make_shared(gfg); } gtsam::DecisionTreeFactor toDecisionTreeFactor( diff --git a/include/dcsam/DCFactor.h b/include/dcsam/DCFactor.h index 7972e6d..055d75d 100644 --- a/include/dcsam/DCFactor.h +++ b/include/dcsam/DCFactor.h @@ -86,6 +86,8 @@ class DCFactor : public gtsam::Factor { const gtsam::Values& continuousVals, const gtsam::DiscreteFactor::Values& discreteVals) const = 0; + using Base::error; // Removes warning about hiding the base class error function. + /** * Linearize the error function with respect to the continuous * variables (given in `keys_`) at the point specified by `continuousVals`. @@ -99,7 +101,7 @@ class DCFactor : public gtsam::Factor { * @param discreteVals - Likewise, assignment to the discrete variables in * `discreteKeys__`. */ - virtual boost::shared_ptr linearize( + virtual std::shared_ptr linearize( const gtsam::Values& continuousVals, const DiscreteValues& discreteVals) const = 0; @@ -155,7 +157,7 @@ class DCFactor : public gtsam::Factor { */ virtual gtsam::DecisionTreeFactor toDecisionTreeFactor( const gtsam::Values& continuousVals, - const DiscreteValues& discreteVals) const { + [[maybe_unused]] const DiscreteValues& discreteVals) const { gtsam::DecisionTreeFactor converted; for (const gtsam::DiscreteKey& dkey : discreteKeys_) { std::vector probs = evalProbs(dkey, continuousVals); @@ -175,7 +177,7 @@ class DCFactor : public gtsam::Factor { * TODO(Kurran) is this the cleanest way to do this? Seems necessary for the * DCMaxMixtureFactor implementations etc... */ - virtual double logNormalizingConstant(const gtsam::Values& values) const { + virtual double logNormalizingConstant([[maybe_unused]] const gtsam::Values& values) const { throw std::logic_error( "Normalizing constant not implemented." "One or more of the factors in use requires access to the normalization" @@ -196,22 +198,22 @@ class DCFactor : public gtsam::Factor { gtsam::Matrix infoMat; // NOTE: This is sloppy, is there a cleaner way? - boost::shared_ptr fPtr = - boost::make_shared(factor); - boost::shared_ptr factorPtr(fPtr); + std::shared_ptr fPtr = + std::make_shared(factor); + std::shared_ptr factorPtr(fPtr); // If this is a NoiseModelFactor, we'll use its noiseModel to // otherwise noiseModelFactor will be nullptr - boost::shared_ptr noiseModelFactor = - boost::dynamic_pointer_cast(factorPtr); + std::shared_ptr noiseModelFactor = + std::dynamic_pointer_cast(factorPtr); if (noiseModelFactor) { // If dynamic cast to NoiseModelFactor succeeded, see if the noise model // is Gaussian gtsam::noiseModel::Base::shared_ptr noiseModel = noiseModelFactor->noiseModel(); - boost::shared_ptr gaussianNoiseModel = - boost::dynamic_pointer_cast(noiseModel); + std::shared_ptr gaussianNoiseModel = + std::dynamic_pointer_cast(noiseModel); if (gaussianNoiseModel) { // If the noise model is Gaussian, retrieve the information matrix infoMat = gaussianNoiseModel->information(); @@ -220,7 +222,7 @@ class DCFactor : public gtsam::Factor { // something with a normalized noise model // TODO(kevin): does this make sense to do? I think maybe not in // general? Should we just yell at the user? - boost::shared_ptr gaussianFactor = + std::shared_ptr gaussianFactor = factor.linearize(values); infoMat = gaussianFactor->information(); } diff --git a/include/dcsam/DCMaxMixtureFactor.h b/include/dcsam/DCMaxMixtureFactor.h index 299d1d6..aaebb5d 100644 --- a/include/dcsam/DCMaxMixtureFactor.h +++ b/include/dcsam/DCMaxMixtureFactor.h @@ -120,7 +120,7 @@ class DCMaxMixtureFactor : public DCFactor { return ((log_weights_ == f.log_weights_) && (normalized_ == f.normalized_)); } - boost::shared_ptr linearize( + std::shared_ptr linearize( const gtsam::Values& continuousVals, const DiscreteValues& discreteVals) const override { size_t min_error_idx = getActiveFactorIdx(continuousVals, discreteVals); diff --git a/include/dcsam/DCMixtureFactor.h b/include/dcsam/DCMixtureFactor.h index 99c9e0c..5f34164 100644 --- a/include/dcsam/DCMixtureFactor.h +++ b/include/dcsam/DCMixtureFactor.h @@ -102,7 +102,7 @@ class DCMixtureFactor : public DCFactor { (normalized_ == f.normalized_)); } - boost::shared_ptr linearize( + std::shared_ptr linearize( const gtsam::Values& continuousVals, const DiscreteValues& discreteVals) const override { // Retrieve the assignment to our discrete key. @@ -112,6 +112,12 @@ class DCMixtureFactor : public DCFactor { // error. return factors_[assignment].linearize(continuousVals); } + + void print(const std::string& s = "DCMixtureFactor:\n", + const gtsam::KeyFormatter& formatter = + gtsam::DefaultKeyFormatter) const override { + Base::print(s, formatter); + } }; } // namespace dcsam diff --git a/include/dcsam/DiscreteMarginalsOrdered.h b/include/dcsam/DiscreteMarginalsOrdered.h index 61f0e12..c95ed6a 100644 --- a/include/dcsam/DiscreteMarginalsOrdered.h +++ b/include/dcsam/DiscreteMarginalsOrdered.h @@ -54,7 +54,9 @@ class DiscreteMarginalsOrdered : public gtsam::DiscreteMarginals { } // sum out frontals to get the factor on the separator. - gtsam::DecisionTreeFactor::shared_ptr sum = product.sum(frontalKeys); + gtsam::DecisionTreeFactor::shared_ptr sum = + std::dynamic_pointer_cast( + product.sum(frontalKeys)); // NOTE: Sum keys seems to be empty often - is this normal? // Ordering keys for the conditional so that frontalKeys is in front. diff --git a/include/dcsam/DiscretePriorFactor.h b/include/dcsam/DiscretePriorFactor.h index 814ab11..79e0fb2 100644 --- a/include/dcsam/DiscretePriorFactor.h +++ b/include/dcsam/DiscretePriorFactor.h @@ -78,11 +78,63 @@ class DiscretePriorFactor : public gtsam::DiscreteFactor { return toDecisionTreeFactor() * f; } - double operator()(const DiscreteValues& values) const override { + double operator()(const DiscreteValues& values) const { size_t assignment = values.at(dk_.first); return probs_[assignment]; } + virtual double evaluate( + const gtsam::Assignment& values) const override { + return this->operator()(DiscreteValues(values)); + } + + virtual DiscreteFactor::shared_ptr operator*(double s) const override { + return toDecisionTreeFactor() * s; + } + + virtual DiscreteFactor::shared_ptr multiply( + const DiscreteFactor::shared_ptr& df) const override { + return df->multiply( + std::make_shared(toDecisionTreeFactor())); + } + + /// divide by DiscreteFactor::shared_ptr f (safely) + virtual DiscreteFactor::shared_ptr operator/( + const DiscreteFactor::shared_ptr& df) const override { + throw std::logic_error("Not implemented: operator/."); + } + + /// Create new factor by summing all values with the same separator values + DiscreteFactor::shared_ptr sum(size_t nrFrontals) const override { + return toDecisionTreeFactor().sum(nrFrontals); + } + + /// Create new factor by summing all values with the same separator values + DiscreteFactor::shared_ptr sum(const gtsam::Ordering& keys) const override { + return toDecisionTreeFactor().sum(keys); + } + + /// Find the maximum value in the factor. + double max() const override { return toDecisionTreeFactor().max(); }; + + /// Create new factor by maximizing over all values with the same separator. + DiscreteFactor::shared_ptr max(size_t nrFrontals) const override { + return toDecisionTreeFactor().max(nrFrontals); + } + + /// Create new factor by maximizing over all values with the same separator. + DiscreteFactor::shared_ptr max(const gtsam::Ordering& keys) const override { + return toDecisionTreeFactor().max(keys); + } + + virtual uint64_t nrValues() const override { return probs_.size(); } + + /// Restrict the factor to the given assignment. + virtual DiscreteFactor::shared_ptr restrict( + const DiscreteValues& assignment) const override { + return toDecisionTreeFactor().restrict(assignment); + } + std::string markdown(const gtsam::KeyFormatter& keyFormatter, const Names& names) const override { return toDecisionTreeFactor().markdown(keyFormatter, names); diff --git a/include/dcsam/HybridFactorGraph.h b/include/dcsam/HybridFactorGraph.h index c10f026..a6c2cfd 100644 --- a/include/dcsam/HybridFactorGraph.h +++ b/include/dcsam/HybridFactorGraph.h @@ -37,15 +37,15 @@ class HybridFactorGraph { template void push_nonlinear(const NonlinearFactorType &nonlinearFactor) { nonlinearGraph_.push_back( - boost::make_shared(nonlinearFactor)); + std::make_shared(nonlinearFactor)); } /** * Add a nonlinear factor *pointer* to the internal nonlinear factor graph - * @param nonlinearFactor - boost::shared_ptr to the factor to add + * @param nonlinearFactor - std::shared_ptr to the factor to add */ void push_nonlinear( - boost::shared_ptr nonlinearFactor); + std::shared_ptr nonlinearFactor); /** * Add a discrete factor to the internal discrete graph @@ -54,14 +54,14 @@ class HybridFactorGraph { template void push_discrete(const DiscreteFactorType &discreteFactor) { discreteGraph_.push_back( - boost::make_shared(discreteFactor)); + std::make_shared(discreteFactor)); } /** * Add a discrete factor *pointer* to the internal discrete graph - * @param discreteFactor - boost::shared_ptr to the factor to add + * @param discreteFactor - std::shared_ptr to the factor to add */ - void push_discrete(boost::shared_ptr discreteFactor); + void push_discrete(std::shared_ptr discreteFactor); /** * Add a discrete-continuous (DC) factor to the internal DC graph @@ -69,14 +69,14 @@ class HybridFactorGraph { */ template void push_dc(const DCFactorType &dcFactor) { - dcGraph_.push_back(boost::make_shared(dcFactor)); + dcGraph_.push_back(std::make_shared(dcFactor)); } /** * Add a discrete-continuous (DC) factor *pointer* to the internal DC graph - * @param dcFactor - boost::shared_ptr to the factor to add + * @param dcFactor - std::shared_ptr to the factor to add */ - void push_dc(boost::shared_ptr dcFactor); + void push_dc(std::shared_ptr dcFactor); /** * Simply prints the factor graph. diff --git a/include/dcsam/SemanticBearingRangeFactor.h b/include/dcsam/SemanticBearingRangeFactor.h index 44368fd..b613971 100644 --- a/include/dcsam/SemanticBearingRangeFactor.h +++ b/include/dcsam/SemanticBearingRangeFactor.h @@ -89,7 +89,7 @@ class SemanticBearingRangeFactor : public DCFactor { // dim is the dimension of the underlying bearingrange factor size_t dim() const override { return factor_.dim(); } - boost::shared_ptr linearize( + std::shared_ptr linearize( const gtsam::Values& continuousVals, const DiscreteValues& discreteVals) const override { return factor_.linearize(continuousVals); diff --git a/src/DCSAM.cpp b/src/DCSAM.cpp index 296725d..dd2584d 100644 --- a/src/DCSAM.cpp +++ b/src/DCSAM.cpp @@ -65,7 +65,7 @@ void DCSAM::update(const gtsam::NonlinearFactorGraph &graph, for (auto &dcfactor : dcfg) { DCDiscreteFactor dcDiscreteFactor(dcfactor); auto sharedDiscrete = - boost::make_shared(dcDiscreteFactor); + std::make_shared(dcDiscreteFactor); discreteCombined.push_back(sharedDiscrete); dcDiscreteFactors_.push_back(sharedDiscrete); } @@ -84,7 +84,7 @@ void DCSAM::update(const gtsam::NonlinearFactorGraph &graph, for (auto &dcfactor : dcfg) { DCContinuousFactor dcContinuousFactor(dcfactor); auto sharedContinuous = - boost::make_shared(dcContinuousFactor); + std::make_shared(dcContinuousFactor); sharedContinuous->updateDiscrete(currDiscrete_); combined.push_back(sharedContinuous); dcContinuousFactors_.push_back(sharedContinuous); @@ -124,8 +124,8 @@ void DCSAM::updateDiscreteInfo(const gtsam::Values &continuousVals, const DiscreteValues &discreteVals) { if (continuousVals.empty()) return; for (auto factor : dcDiscreteFactors_) { - boost::shared_ptr dcDiscrete = - boost::static_pointer_cast(factor); + std::shared_ptr dcDiscrete = + std::static_pointer_cast(factor); dcDiscrete->updateContinuous(continuousVals); dcDiscrete->updateDiscrete(discreteVals); } @@ -142,8 +142,9 @@ void DCSAM::updateContinuousInfo(const DiscreteValues &discreteVals, gtsam::ISAM2UpdateParams updateParams; gtsam::FastMap newAffectedKeys; for (size_t j = 0; j < dcContinuousFactors_.size(); j++) { - boost::shared_ptr dcContinuousFactor = - boost::static_pointer_cast(dcContinuousFactors_[j]); + // dcContinuousFactors_[j]->print(); + std::shared_ptr dcContinuousFactor = + std::static_pointer_cast(dcContinuousFactors_[j]); dcContinuousFactor->updateDiscrete(discreteVals); for (const gtsam::Key &k : dcContinuousFactor->keys()) { newAffectedKeys[j].insert(k); diff --git a/src/HybridFactorGraph.cpp b/src/HybridFactorGraph.cpp index 6985e56..448f79f 100644 --- a/src/HybridFactorGraph.cpp +++ b/src/HybridFactorGraph.cpp @@ -12,16 +12,16 @@ namespace dcsam { HybridFactorGraph::HybridFactorGraph() {} void HybridFactorGraph::push_nonlinear( - boost::shared_ptr nonlinearFactor) { + std::shared_ptr nonlinearFactor) { nonlinearGraph_.push_back(nonlinearFactor); } void HybridFactorGraph::push_discrete( - boost::shared_ptr discreteFactor) { + std::shared_ptr discreteFactor) { discreteGraph_.push_back(discreteFactor); } -void HybridFactorGraph::push_dc(boost::shared_ptr dcFactor) { +void HybridFactorGraph::push_dc(std::shared_ptr dcFactor) { dcGraph_.push_back(dcFactor); } diff --git a/tests/testDCSAM.cpp b/tests/testDCSAM.cpp index ad8a3bc..e0a40bc 100644 --- a/tests/testDCSAM.cpp +++ b/tests/testDCSAM.cpp @@ -141,8 +141,8 @@ TEST(TestSuite, smart_discrete_prior_factor) { // Update the factor const std::vector newProbs{0.9, 0.1}; - boost::shared_ptr smart = - boost::dynamic_pointer_cast(dfg[0]); + std::shared_ptr smart = + std::dynamic_pointer_cast(dfg[0]); if (smart) smart->updateProbs(newProbs); // Solve @@ -203,8 +203,8 @@ TEST(TestSuite, dcdiscrete_mixture) { std::vector> factorComponents{f1, fNullHypo}; - dcsam::DCMixtureFactor> dcMixture(keys, dk, - factorComponents); + dcsam::DCMixtureFactor> dcMixture( + keys, dk, factorComponents); dcfg.push_back(dcMixture); gtsam::DiscreteKey dkTest = dcMixture.discreteKeys()[0]; @@ -232,8 +232,8 @@ TEST(TestSuite, dcdiscrete_mixture) { // Update continuous info for (size_t j = 0; j < dfg.size(); j++) { - boost::shared_ptr dcDiscreteFactor = - boost::dynamic_pointer_cast(dfg[j]); + std::shared_ptr dcDiscreteFactor = + std::dynamic_pointer_cast(dfg[j]); if (dcDiscreteFactor) { dcDiscreteFactor->updateContinuous(initialGuess); dcDiscreteFactor->updateDiscrete(initialGuessDiscrete); @@ -297,8 +297,8 @@ TEST(TestSuite, dccontinuous_mixture) { gtsam::PriorFactor fNullHypo(x1, loc, prior_noiseNullHypo); std::vector> factorComponents{f1, fNullHypo}; - dcsam::DCMixtureFactor> dcMixture(keys, dk, - factorComponents); + dcsam::DCMixtureFactor> dcMixture( + keys, dk, factorComponents); dcfg.push_back(dcMixture); gtsam::DiscreteKey dkTest = dcMixture.discreteKeys()[0]; @@ -378,8 +378,8 @@ TEST(TestSuite, dccontinuous_mixture) { // Update continuous info inside DCDiscreteFactor for (size_t j = 0; j < dfg.size(); j++) { - boost::shared_ptr dcDiscreteFactor = - boost::dynamic_pointer_cast(dfg[j]); + std::shared_ptr dcDiscreteFactor = + std::dynamic_pointer_cast(dfg[j]); if (dcDiscreteFactor) { dcDiscreteFactor->updateContinuous(initialGuess); dcDiscreteFactor->updateDiscrete(initialGuessDiscrete); @@ -401,8 +401,8 @@ TEST(TestSuite, dccontinuous_mixture) { // Update discrete info inside DCContinuousFactor for (size_t j = 0; j < graph.size(); j++) { - boost::shared_ptr dcContinuousFactor = - boost::dynamic_pointer_cast(graph[j]); + std::shared_ptr dcContinuousFactor = + std::dynamic_pointer_cast(graph[j]); if (dcContinuousFactor) dcContinuousFactor->updateDiscrete(mostProbableEstimate); } @@ -431,8 +431,8 @@ TEST(TestSuite, dccontinuous_mixture) { // Now update the continuous info in the discrete solver for (size_t j = 0; j < dfg.size(); j++) { - boost::shared_ptr dcDiscreteFactor = - boost::dynamic_pointer_cast(dfg[j]); + std::shared_ptr dcDiscreteFactor = + std::dynamic_pointer_cast(dfg[j]); if (dcDiscreteFactor) dcDiscreteFactor->updateContinuous(values); // NOTE: we won't updateDiscrete explicitly here anymore, because we don't // need to. @@ -478,8 +478,8 @@ TEST(TestSuite, simple_mixture_factor) { gtsam::PriorFactor fNullHypo(x1, loc, prior_noiseNullHypo); std::vector> factorComponents{f1, fNullHypo}; - dcsam::DCMixtureFactor> dcMixture(keys, dk, - factorComponents); + dcsam::DCMixtureFactor> dcMixture( + keys, dk, factorComponents); // Make an empty hybrid factor graph dcsam::HybridFactorGraph hfg; @@ -1554,7 +1554,7 @@ TEST(TestSuite, simple_dcemfactor) { } /** - * This is for testing the behavior of duplicating discrete factors + * This is for testing the behavior of duplicating discrete factors */ TEST(TestSuite, factor_duplicate) { // Make a factor graph @@ -1654,7 +1654,7 @@ TEST(TestSuite, factor_duplicate) { hfg.clear(); initialGuess.clear(); } - + dcsam::DCValues dcvals = dcsam.calculateEstimate(); size_t mpeClassL1 = dcvals.discrete.at(lc1); EXPECT_EQ(mpeClassL1, 0);