Merge pull request #1406 from kartikarcot/verdant/smart_ptrs
						commit
						5400bd6670
					
				| 
						 | 
				
			
			@ -271,7 +271,7 @@ color{red}{// Make 'private' any typedefs that must be redefined in derived
 | 
			
		|||
 | 
			
		||||
\begin_layout Plain Layout
 | 
			
		||||
 | 
			
		||||
    typedef boost::shared_ptr<This> shared_ptr;  ///< Shared pointer to
 | 
			
		||||
    typedef std::shared_ptr<This> shared_ptr;  ///< Shared pointer to
 | 
			
		||||
 this
 | 
			
		||||
\end_layout
 | 
			
		||||
 | 
			
		||||
| 
						 | 
				
			
			@ -304,7 +304,7 @@ color{red}{// Make 'public' the typedefs that will be valid in the derived
 | 
			
		|||
 | 
			
		||||
\begin_layout Plain Layout
 | 
			
		||||
 | 
			
		||||
    typedef boost::shared_ptr<FACTOR> sharedFactor; ///< Shared pointer
 | 
			
		||||
    typedef std::shared_ptr<FACTOR> sharedFactor; ///< Shared pointer
 | 
			
		||||
 to a factor
 | 
			
		||||
\end_layout
 | 
			
		||||
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -20,7 +20,6 @@
 | 
			
		|||
#include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
 | 
			
		||||
#include <gtsam/geometry/PinholeCamera.h>
 | 
			
		||||
#include <gtsam/geometry/Cal3_S2.h>
 | 
			
		||||
#include <boost/make_shared.hpp>
 | 
			
		||||
 | 
			
		||||
using namespace gtsam;
 | 
			
		||||
using namespace gtsam::noiseModel;
 | 
			
		||||
| 
						 | 
				
			
			@ -70,7 +69,7 @@ int main(int argc, char* argv[]) {
 | 
			
		|||
  /* 2. add factors to the graph */
 | 
			
		||||
  // add measurement factors
 | 
			
		||||
  SharedDiagonal measurementNoise = Diagonal::Sigmas(Vector2(0.5, 0.5));
 | 
			
		||||
  boost::shared_ptr<ResectioningFactor> factor;
 | 
			
		||||
  std::shared_ptr<ResectioningFactor> factor;
 | 
			
		||||
  graph.emplace_shared<ResectioningFactor>(measurementNoise, X(1), calib,
 | 
			
		||||
          Point2(55, 45), Point3(10, 10, 0));
 | 
			
		||||
  graph.emplace_shared<ResectioningFactor>(measurementNoise, X(1), calib,
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -95,7 +95,7 @@ Vector10 readInitialState(ifstream& file) {
 | 
			
		|||
  return initial_state;
 | 
			
		||||
}
 | 
			
		||||
 | 
			
		||||
boost::shared_ptr<PreintegratedCombinedMeasurements::Params> imuParams() {
 | 
			
		||||
std::shared_ptr<PreintegratedCombinedMeasurements::Params> imuParams() {
 | 
			
		||||
  // We use the sensor specs to build the noise model for the IMU factor.
 | 
			
		||||
  double accel_noise_sigma = 0.0003924;
 | 
			
		||||
  double gyro_noise_sigma = 0.000205689024915;
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -61,7 +61,7 @@ using symbol_shorthand::X;  // for poses
 | 
			
		|||
/* ************************************************************************* */
 | 
			
		||||
int main(int argc, char *argv[]) {
 | 
			
		||||
  // Define the camera calibration parameters
 | 
			
		||||
  auto K = boost::make_shared<Cal3Fisheye>(
 | 
			
		||||
  auto K = std::make_shared<Cal3Fisheye>(
 | 
			
		||||
      278.66, 278.48, 0.0, 319.75, 241.96, -0.013721808247486035,
 | 
			
		||||
      0.020727425669427896, -0.012786476702685545, 0.0025242267320687625);
 | 
			
		||||
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -82,7 +82,7 @@ po::variables_map parseOptions(int argc, char* argv[]) {
 | 
			
		|||
  return vm;
 | 
			
		||||
}
 | 
			
		||||
 | 
			
		||||
boost::shared_ptr<PreintegratedCombinedMeasurements::Params> imuParams() {
 | 
			
		||||
std::shared_ptr<PreintegratedCombinedMeasurements::Params> imuParams() {
 | 
			
		||||
  // We use the sensor specs to build the noise model for the IMU factor.
 | 
			
		||||
  double accel_noise_sigma = 0.0003924;
 | 
			
		||||
  double gyro_noise_sigma = 0.000205689024915;
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -115,7 +115,7 @@ int main(int argc, char* argv[]) {
 | 
			
		|||
        Vector6 covvec;
 | 
			
		||||
        covvec << 0.1, 0.1, 0.1, 0.1, 0.1, 0.1;
 | 
			
		||||
        auto cov = noiseModel::Diagonal::Variances(covvec);
 | 
			
		||||
        auto f = boost::make_shared<BetweenFactor<imuBias::ConstantBias> >(
 | 
			
		||||
        auto f = std::make_shared<BetweenFactor<imuBias::ConstantBias> >(
 | 
			
		||||
            b1, b2, imuBias::ConstantBias(), cov);
 | 
			
		||||
        newgraph.add(f);
 | 
			
		||||
        initialEstimate.insert(biasKey, imuBias::ConstantBias());
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -76,7 +76,7 @@ class UnaryFactor: public NoiseModelFactorN<Pose2> {
 | 
			
		|||
  using NoiseModelFactor1<Pose2>::evaluateError;
 | 
			
		||||
 | 
			
		||||
  /// shorthand for a smart pointer to a factor
 | 
			
		||||
  typedef boost::shared_ptr<UnaryFactor> shared_ptr;
 | 
			
		||||
  typedef std::shared_ptr<UnaryFactor> shared_ptr;
 | 
			
		||||
 | 
			
		||||
  // The constructor requires the variable key, the (X, Y) measurement value, and the noise model
 | 
			
		||||
  UnaryFactor(Key j, double x, double y, const SharedNoiseModel& model):
 | 
			
		||||
| 
						 | 
				
			
			@ -105,7 +105,7 @@ class UnaryFactor: public NoiseModelFactorN<Pose2> {
 | 
			
		|||
  // circumstances, the following code that employs the default copy constructor should
 | 
			
		||||
  // work fine.
 | 
			
		||||
  gtsam::NonlinearFactor::shared_ptr clone() const override {
 | 
			
		||||
    return boost::static_pointer_cast<gtsam::NonlinearFactor>(
 | 
			
		||||
    return std::static_pointer_cast<gtsam::NonlinearFactor>(
 | 
			
		||||
        gtsam::NonlinearFactor::shared_ptr(new UnaryFactor(*this))); }
 | 
			
		||||
 | 
			
		||||
  // Additionally, we encourage you the use of unit testing your custom factors,
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -69,7 +69,7 @@ int main(int argc, char** argv) {
 | 
			
		|||
  // addition, the *type* of the iterativeParams decides on the type of
 | 
			
		||||
  // iterative solver, in this case the SPCG (subgraph PCG)
 | 
			
		||||
  parameters.linearSolverType = NonlinearOptimizerParams::Iterative;
 | 
			
		||||
  parameters.iterativeParams = boost::make_shared<SubgraphSolverParameters>();
 | 
			
		||||
  parameters.iterativeParams = std::make_shared<SubgraphSolverParameters>();
 | 
			
		||||
 | 
			
		||||
  LevenbergMarquardtOptimizer optimizer(graph, initialEstimate, parameters);
 | 
			
		||||
  Values result = optimizer.optimize();
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -65,9 +65,9 @@ int main(const int argc, const char *argv[]) {
 | 
			
		|||
      simpleInitial.insert(key, initial->at(key_value.key));
 | 
			
		||||
    }
 | 
			
		||||
    NonlinearFactorGraph simpleGraph;
 | 
			
		||||
    for(const boost::shared_ptr<NonlinearFactor>& factor: *graph) {
 | 
			
		||||
      boost::shared_ptr<BetweenFactor<Pose3> > pose3Between =
 | 
			
		||||
          boost::dynamic_pointer_cast<BetweenFactor<Pose3> >(factor);
 | 
			
		||||
    for(const std::shared_ptr<NonlinearFactor>& factor: *graph) {
 | 
			
		||||
      std::shared_ptr<BetweenFactor<Pose3> > pose3Between =
 | 
			
		||||
          std::dynamic_pointer_cast<BetweenFactor<Pose3> >(factor);
 | 
			
		||||
      if (pose3Between){
 | 
			
		||||
        Key key1, key2;
 | 
			
		||||
        if(add){
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -112,7 +112,7 @@ int main(int argc, char* argv[]) {
 | 
			
		|||
  for (size_t j = 0; j < points.size(); ++j) {
 | 
			
		||||
 | 
			
		||||
    // The graph stores Factor shared_ptrs, so we cast back to a SmartFactor first
 | 
			
		||||
    SmartFactor::shared_ptr smart = boost::dynamic_pointer_cast<SmartFactor>(graph[j]);
 | 
			
		||||
    SmartFactor::shared_ptr smart = std::dynamic_pointer_cast<SmartFactor>(graph[j]);
 | 
			
		||||
    if (smart) {
 | 
			
		||||
      // The output of point() is in std::optional<Point3>, as sometimes
 | 
			
		||||
      // the triangulation operation inside smart factor will encounter degeneracy.
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -93,9 +93,9 @@ int main(int argc, char* argv[]) {
 | 
			
		|||
  parameters.relativeErrorTol = 1e-10;
 | 
			
		||||
  parameters.maxIterations = 500;
 | 
			
		||||
  PCGSolverParameters::shared_ptr pcg =
 | 
			
		||||
      boost::make_shared<PCGSolverParameters>();
 | 
			
		||||
      std::make_shared<PCGSolverParameters>();
 | 
			
		||||
  pcg->preconditioner_ =
 | 
			
		||||
      boost::make_shared<BlockJacobiPreconditionerParameters>();
 | 
			
		||||
      std::make_shared<BlockJacobiPreconditionerParameters>();
 | 
			
		||||
  // Following is crucial:
 | 
			
		||||
  pcg->setEpsilon_abs(1e-10);
 | 
			
		||||
  pcg->setEpsilon_rel(1e-10);
 | 
			
		||||
| 
						 | 
				
			
			@ -108,7 +108,7 @@ int main(int argc, char* argv[]) {
 | 
			
		|||
  result.print("Final results:\n");
 | 
			
		||||
  Values landmark_result;
 | 
			
		||||
  for (size_t j = 0; j < points.size(); ++j) {
 | 
			
		||||
    auto smart = boost::dynamic_pointer_cast<SmartFactor>(graph[j]);
 | 
			
		||||
    auto smart = std::dynamic_pointer_cast<SmartFactor>(graph[j]);
 | 
			
		||||
    if (smart) {
 | 
			
		||||
      std::optional<Point3> point = smart->point(result);
 | 
			
		||||
      if (point)  // ignore if std::optional return nullptr
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -79,7 +79,7 @@ double chi2_red(const gtsam::NonlinearFactorGraph& graph, const gtsam::Values& c
 | 
			
		|||
  // the factor graph already includes a factor for the prior/equality constraint.
 | 
			
		||||
  //  double dof = graph.size() - config.size();
 | 
			
		||||
  int graph_dim = 0;
 | 
			
		||||
  for(const boost::shared_ptr<gtsam::NonlinearFactor>& nlf: graph) {
 | 
			
		||||
  for(const std::shared_ptr<gtsam::NonlinearFactor>& nlf: graph) {
 | 
			
		||||
    graph_dim += (int)nlf->dim();
 | 
			
		||||
  }
 | 
			
		||||
  double dof = double(graph_dim) - double(config.dim()); // kaess: changed to dim
 | 
			
		||||
| 
						 | 
				
			
			@ -259,7 +259,7 @@ void runIncremental()
 | 
			
		|||
  while(nextMeasurement < datasetMeasurements.size())
 | 
			
		||||
  {
 | 
			
		||||
    if(BetweenFactor<Pose>::shared_ptr factor =
 | 
			
		||||
      boost::dynamic_pointer_cast<BetweenFactor<Pose> >(datasetMeasurements[nextMeasurement]))
 | 
			
		||||
      std::dynamic_pointer_cast<BetweenFactor<Pose> >(datasetMeasurements[nextMeasurement]))
 | 
			
		||||
    {
 | 
			
		||||
      Key key1 = factor->key<1>(), key2 = factor->key<2>();
 | 
			
		||||
      if(((int)key1 >= firstStep && key1 < key2) || ((int)key2 >= firstStep && key2 < key1)) {
 | 
			
		||||
| 
						 | 
				
			
			@ -310,7 +310,7 @@ void runIncremental()
 | 
			
		|||
      NonlinearFactor::shared_ptr measurementf = datasetMeasurements[nextMeasurement];
 | 
			
		||||
 | 
			
		||||
      if(BetweenFactor<Pose>::shared_ptr factor =
 | 
			
		||||
        boost::dynamic_pointer_cast<BetweenFactor<Pose> >(measurementf))
 | 
			
		||||
        std::dynamic_pointer_cast<BetweenFactor<Pose> >(measurementf))
 | 
			
		||||
      {
 | 
			
		||||
        // Stop collecting measurements that are for future steps
 | 
			
		||||
        if(factor->key<1>() > step || factor->key<2>() > step)
 | 
			
		||||
| 
						 | 
				
			
			@ -346,7 +346,7 @@ void runIncremental()
 | 
			
		|||
        }
 | 
			
		||||
      }
 | 
			
		||||
      else if(BearingRangeFactor<Pose, Point2>::shared_ptr factor =
 | 
			
		||||
        boost::dynamic_pointer_cast<BearingRangeFactor<Pose, Point2> >(measurementf))
 | 
			
		||||
        std::dynamic_pointer_cast<BearingRangeFactor<Pose, Point2> >(measurementf))
 | 
			
		||||
      {
 | 
			
		||||
        Key poseKey = factor->keys()[0], lmKey = factor->keys()[1];
 | 
			
		||||
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -122,7 +122,7 @@ int main(int argc, char* argv[]) {
 | 
			
		|||
  Matrix errorsDLTOpt = Matrix::Zero(nrTrials, 3);
 | 
			
		||||
 | 
			
		||||
  double rank_tol = 1e-9;
 | 
			
		||||
  boost::shared_ptr<Cal3_S2> calib = boost::make_shared<Cal3_S2>();
 | 
			
		||||
  std::shared_ptr<Cal3_S2> calib = std::make_shared<Cal3_S2>();
 | 
			
		||||
  std::chrono::nanoseconds durationDLT;
 | 
			
		||||
  std::chrono::nanoseconds durationDLTOpt;
 | 
			
		||||
  std::chrono::nanoseconds durationLOST;
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -17,8 +17,8 @@
 | 
			
		|||
 */
 | 
			
		||||
 | 
			
		||||
#include <gtsam/base/DSFVector.h>
 | 
			
		||||
#include <boost/make_shared.hpp>
 | 
			
		||||
#include <algorithm>
 | 
			
		||||
#include <cassert>
 | 
			
		||||
 | 
			
		||||
using namespace std;
 | 
			
		||||
 | 
			
		||||
| 
						 | 
				
			
			@ -26,14 +26,14 @@ namespace gtsam {
 | 
			
		|||
 | 
			
		||||
/* ************************************************************************* */
 | 
			
		||||
DSFBase::DSFBase(const size_t numNodes) {
 | 
			
		||||
  v_ = boost::make_shared < V > (numNodes);
 | 
			
		||||
  v_ = std::make_shared < V > (numNodes);
 | 
			
		||||
  int index = 0;
 | 
			
		||||
  for (V::iterator it = v_->begin(); it != v_->end(); it++, index++)
 | 
			
		||||
    *it = index;
 | 
			
		||||
}
 | 
			
		||||
 | 
			
		||||
/* ************************************************************************* */
 | 
			
		||||
DSFBase::DSFBase(const boost::shared_ptr<V>& v_in) {
 | 
			
		||||
DSFBase::DSFBase(const std::shared_ptr<V>& v_in) {
 | 
			
		||||
  v_ = v_in;
 | 
			
		||||
  int index = 0;
 | 
			
		||||
  for (V::iterator it = v_->begin(); it != v_->end(); it++, index++)
 | 
			
		||||
| 
						 | 
				
			
			@ -69,7 +69,7 @@ DSFVector::DSFVector(const std::vector<size_t>& keys) :
 | 
			
		|||
}
 | 
			
		||||
 | 
			
		||||
/* ************************************************************************* */
 | 
			
		||||
DSFVector::DSFVector(const boost::shared_ptr<V>& v_in,
 | 
			
		||||
DSFVector::DSFVector(const std::shared_ptr<V>& v_in,
 | 
			
		||||
    const std::vector<size_t>& keys) :
 | 
			
		||||
    DSFBase(v_in), keys_(keys) {
 | 
			
		||||
  assert(*(std::max_element(keys.begin(), keys.end()))<v_in->size());
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -21,7 +21,7 @@
 | 
			
		|||
#include <gtsam/dllexport.h>
 | 
			
		||||
#include <gtsam/global_includes.h>
 | 
			
		||||
 | 
			
		||||
#include <boost/shared_ptr.hpp>
 | 
			
		||||
#include <memory>
 | 
			
		||||
 | 
			
		||||
#include <vector>
 | 
			
		||||
#include <set>
 | 
			
		||||
| 
						 | 
				
			
			@ -41,14 +41,14 @@ public:
 | 
			
		|||
  typedef std::vector<size_t> V; ///< Vector of ints
 | 
			
		||||
 | 
			
		||||
private:
 | 
			
		||||
  boost::shared_ptr<V> v_;///< Stores parent pointers, representative iff v[i]==i
 | 
			
		||||
  std::shared_ptr<V> v_;///< Stores parent pointers, representative iff v[i]==i
 | 
			
		||||
 | 
			
		||||
public:
 | 
			
		||||
  /// Constructor that allocates new memory, allows for keys 0...numNodes-1.
 | 
			
		||||
  DSFBase(const size_t numNodes);
 | 
			
		||||
 | 
			
		||||
  /// Constructor that uses an existing, pre-allocated vector.
 | 
			
		||||
  DSFBase(const boost::shared_ptr<V>& v_in);
 | 
			
		||||
  DSFBase(const std::shared_ptr<V>& v_in);
 | 
			
		||||
 | 
			
		||||
  /// Find the label of the set in which {key} lives.
 | 
			
		||||
  size_t find(size_t key) const;
 | 
			
		||||
| 
						 | 
				
			
			@ -74,7 +74,7 @@ public:
 | 
			
		|||
  DSFVector(const std::vector<size_t>& keys);
 | 
			
		||||
 | 
			
		||||
  /// Constructor that uses existing vectors.
 | 
			
		||||
  DSFVector(const boost::shared_ptr<V>& v_in, const std::vector<size_t>& keys);
 | 
			
		||||
  DSFVector(const std::shared_ptr<V>& v_in, const std::vector<size_t>& keys);
 | 
			
		||||
 | 
			
		||||
  // All operations below loop over all keys and hence are *at least* O(n)
 | 
			
		||||
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -23,7 +23,6 @@
 | 
			
		|||
#include <gtsam/base/types.h>
 | 
			
		||||
#include <gtsam/base/Value.h>
 | 
			
		||||
 | 
			
		||||
#include <boost/make_shared.hpp>
 | 
			
		||||
#include <boost/pool/pool_alloc.hpp>
 | 
			
		||||
 | 
			
		||||
#include <cmath>
 | 
			
		||||
| 
						 | 
				
			
			@ -114,8 +113,8 @@ public:
 | 
			
		|||
    /**
 | 
			
		||||
     * Clone this value (normal clone on the heap, delete with 'delete' operator)
 | 
			
		||||
     */
 | 
			
		||||
    boost::shared_ptr<Value> clone() const override {
 | 
			
		||||
		return boost::allocate_shared<GenericValue>(Eigen::aligned_allocator<GenericValue>(), *this);
 | 
			
		||||
    std::shared_ptr<Value> clone() const override {
 | 
			
		||||
		return std::allocate_shared<GenericValue>(Eigen::aligned_allocator<GenericValue>(), *this);
 | 
			
		||||
    }
 | 
			
		||||
 | 
			
		||||
    /// Generic Value interface version of retract
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -21,7 +21,6 @@
 | 
			
		|||
#include <gtsam/config.h>      // Configuration from CMake
 | 
			
		||||
 | 
			
		||||
#include <gtsam/base/Vector.h>
 | 
			
		||||
#include <boost/make_shared.hpp>
 | 
			
		||||
#include <boost/serialization/nvp.hpp>
 | 
			
		||||
#include <boost/serialization/assume_abstract.hpp>
 | 
			
		||||
#include <memory>
 | 
			
		||||
| 
						 | 
				
			
			@ -45,7 +44,7 @@ namespace gtsam {
 | 
			
		|||
    virtual void deallocate_() const = 0;
 | 
			
		||||
 | 
			
		||||
    /** Clone this value (normal clone on the heap, delete with 'delete' operator) */
 | 
			
		||||
    virtual boost::shared_ptr<Value> clone() const = 0;
 | 
			
		||||
    virtual std::shared_ptr<Value> clone() const = 0;
 | 
			
		||||
 | 
			
		||||
    /** Compare this Value with another for equality. */
 | 
			
		||||
    virtual bool equals_(const Value& other, double tol = 1e-9) const = 0;
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -21,7 +21,6 @@
 | 
			
		|||
 | 
			
		||||
#include <Eigen/Core>
 | 
			
		||||
 | 
			
		||||
#include <boost/make_shared.hpp>
 | 
			
		||||
 | 
			
		||||
#include <type_traits>
 | 
			
		||||
 | 
			
		||||
| 
						 | 
				
			
			@ -34,7 +33,7 @@ namespace gtsam {
 | 
			
		|||
namespace gtsam {
 | 
			
		||||
 | 
			
		||||
  /**
 | 
			
		||||
   * Add our own `make_shared` as a layer of wrapping on `boost::make_shared`
 | 
			
		||||
   * Add our own `make_shared` as a layer of wrapping on `std::make_shared`
 | 
			
		||||
   * This solves the problem with the stock `make_shared` that custom alignment is not respected, causing SEGFAULTs
 | 
			
		||||
   * at runtime, which is notoriously hard to debug.
 | 
			
		||||
   *
 | 
			
		||||
| 
						 | 
				
			
			@ -46,22 +45,22 @@ namespace gtsam {
 | 
			
		|||
   *
 | 
			
		||||
   * This function declaration will only be taken when the above condition is true, so if some object does not need to
 | 
			
		||||
   * be aligned, `gtsam::make_shared` will fall back to the next definition, which is a simple wrapper for
 | 
			
		||||
   * `boost::make_shared`.
 | 
			
		||||
   * `std::make_shared`.
 | 
			
		||||
   *
 | 
			
		||||
   * @tparam T The type of object being constructed
 | 
			
		||||
   * @tparam Args Type of the arguments of the constructor
 | 
			
		||||
   * @param args Arguments of the constructor
 | 
			
		||||
   * @return The object created as a boost::shared_ptr<T>
 | 
			
		||||
   * @return The object created as a std::shared_ptr<T>
 | 
			
		||||
   */
 | 
			
		||||
  template<typename T, typename ... Args>
 | 
			
		||||
  gtsam::enable_if_t<needs_eigen_aligned_allocator<T>::value, boost::shared_ptr<T>> make_shared(Args &&... args) {
 | 
			
		||||
    return boost::allocate_shared<T>(Eigen::aligned_allocator<T>(), std::forward<Args>(args)...);
 | 
			
		||||
  gtsam::enable_if_t<needs_eigen_aligned_allocator<T>::value, std::shared_ptr<T>> make_shared(Args &&... args) {
 | 
			
		||||
    return std::allocate_shared<T>(Eigen::aligned_allocator<T>(), std::forward<Args>(args)...);
 | 
			
		||||
  }
 | 
			
		||||
 | 
			
		||||
  /// Fall back to the boost version if no need for alignment
 | 
			
		||||
  template<typename T, typename ... Args>
 | 
			
		||||
  gtsam::enable_if_t<!needs_eigen_aligned_allocator<T>::value, boost::shared_ptr<T>> make_shared(Args &&... args) {
 | 
			
		||||
    return boost::make_shared<T>(std::forward<Args>(args)...);
 | 
			
		||||
  gtsam::enable_if_t<!needs_eigen_aligned_allocator<T>::value, std::shared_ptr<T>> make_shared(Args &&... args) {
 | 
			
		||||
    return std::make_shared<T>(std::forward<Args>(args)...);
 | 
			
		||||
  }
 | 
			
		||||
 | 
			
		||||
}
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -1,6 +1,13 @@
 | 
			
		|||
// Functionality to serialize std::optional<T> to boost::archive
 | 
			
		||||
// Following this:
 | 
			
		||||
// PR: https://github.com/boostorg/serialization/pull/148/files#
 | 
			
		||||
/* ----------------------------------------------------------------------------
 | 
			
		||||
* Use, modification and distribution is subject to the Boost Software
 | 
			
		||||
* License, Version 1.0. (See accompanying file LICENSE_1_0.txt or copy at
 | 
			
		||||
* http://www.boost.org/LICENSE_1_0.txt)
 | 
			
		||||
 | 
			
		||||
* See http://www.boost.org for updates, documentation, and revision history.
 | 
			
		||||
 | 
			
		||||
* Functionality to serialize std::optional<T> to boost::archive
 | 
			
		||||
* Inspired from this PR: https://github.com/boostorg/serialization/pull/163
 | 
			
		||||
* ---------------------------------------------------------------------------- */
 | 
			
		||||
 | 
			
		||||
#pragma once
 | 
			
		||||
#include <optional>
 | 
			
		||||
| 
						 | 
				
			
			@ -88,8 +95,6 @@ void serialize(Archive& ar, std::optional<T>& t, const unsigned int version) {
 | 
			
		|||
  boost::serialization::split_free(ar, t, version);
 | 
			
		||||
}
 | 
			
		||||
 | 
			
		||||
// derive boost::xml_archive_impl for archiving std::optional<T> with xml
 | 
			
		||||
 | 
			
		||||
}  // namespace serialization
 | 
			
		||||
}  // namespace boost
 | 
			
		||||
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -20,7 +20,6 @@
 | 
			
		|||
 | 
			
		||||
#include <CppUnitLite/TestHarness.h>
 | 
			
		||||
 | 
			
		||||
#include <boost/make_shared.hpp>
 | 
			
		||||
 | 
			
		||||
#include <iostream>
 | 
			
		||||
#include <set>
 | 
			
		||||
| 
						 | 
				
			
			@ -85,7 +84,7 @@ TEST(DSFBase, mergePairwiseMatches) {
 | 
			
		|||
 | 
			
		||||
/* ************************************************************************* */
 | 
			
		||||
TEST(DSFVector, merge2) {
 | 
			
		||||
  boost::shared_ptr<DSFBase::V> v = boost::make_shared<DSFBase::V>(5);
 | 
			
		||||
  std::shared_ptr<DSFBase::V> v = std::make_shared<DSFBase::V>(5);
 | 
			
		||||
  const std::vector<size_t> keys {1, 3};
 | 
			
		||||
  DSFVector dsf(v, keys);
 | 
			
		||||
  dsf.merge(1,3);
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -21,13 +21,12 @@
 | 
			
		|||
 | 
			
		||||
#include <vector>
 | 
			
		||||
#include <list>
 | 
			
		||||
#include <boost/shared_ptr.hpp>
 | 
			
		||||
#include <boost/make_shared.hpp>
 | 
			
		||||
#include <memory>
 | 
			
		||||
 | 
			
		||||
using namespace gtsam;
 | 
			
		||||
 | 
			
		||||
struct TestNode {
 | 
			
		||||
  typedef boost::shared_ptr<TestNode> shared_ptr;
 | 
			
		||||
  typedef std::shared_ptr<TestNode> shared_ptr;
 | 
			
		||||
  int data;
 | 
			
		||||
  std::vector<shared_ptr> children;
 | 
			
		||||
  TestNode() : data(-1) {}
 | 
			
		||||
| 
						 | 
				
			
			@ -48,11 +47,11 @@ TestForest makeTestForest() {
 | 
			
		|||
  //     |
 | 
			
		||||
  //     4
 | 
			
		||||
  TestForest forest;
 | 
			
		||||
  forest.roots_.push_back(boost::make_shared<TestNode>(0));
 | 
			
		||||
  forest.roots_.push_back(boost::make_shared<TestNode>(1));
 | 
			
		||||
  forest.roots_[0]->children.push_back(boost::make_shared<TestNode>(2));
 | 
			
		||||
  forest.roots_[0]->children.push_back(boost::make_shared<TestNode>(3));
 | 
			
		||||
  forest.roots_[0]->children[1]->children.push_back(boost::make_shared<TestNode>(4));
 | 
			
		||||
  forest.roots_.push_back(std::make_shared<TestNode>(0));
 | 
			
		||||
  forest.roots_.push_back(std::make_shared<TestNode>(1));
 | 
			
		||||
  forest.roots_[0]->children.push_back(std::make_shared<TestNode>(2));
 | 
			
		||||
  forest.roots_[0]->children.push_back(std::make_shared<TestNode>(3));
 | 
			
		||||
  forest.roots_[0]->children[1]->children.push_back(std::make_shared<TestNode>(4));
 | 
			
		||||
  return forest;
 | 
			
		||||
}
 | 
			
		||||
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -34,9 +34,9 @@
 | 
			
		|||
namespace gtsam {
 | 
			
		||||
namespace internal {
 | 
			
		||||
 | 
			
		||||
GTSAM_EXPORT boost::shared_ptr<TimingOutline> gTimingRoot(
 | 
			
		||||
GTSAM_EXPORT std::shared_ptr<TimingOutline> gTimingRoot(
 | 
			
		||||
    new TimingOutline("Total", getTicTocID("Total")));
 | 
			
		||||
GTSAM_EXPORT boost::weak_ptr<TimingOutline> gCurrentTimer(gTimingRoot);
 | 
			
		||||
GTSAM_EXPORT std::weak_ptr<TimingOutline> gCurrentTimer(gTimingRoot);
 | 
			
		||||
 | 
			
		||||
/* ************************************************************************* */
 | 
			
		||||
// Implementation of TimingOutline
 | 
			
		||||
| 
						 | 
				
			
			@ -83,7 +83,7 @@ void TimingOutline::print(const std::string& outline) const {
 | 
			
		|||
      << n_ << " times, " << wall() << " wall, " << secs() << " children, min: "
 | 
			
		||||
      << min() << " max: " << max() << ")\n";
 | 
			
		||||
  // Order children
 | 
			
		||||
  typedef FastMap<size_t, boost::shared_ptr<TimingOutline> > ChildOrder;
 | 
			
		||||
  typedef FastMap<size_t, std::shared_ptr<TimingOutline> > ChildOrder;
 | 
			
		||||
  ChildOrder childOrder;
 | 
			
		||||
  for(const ChildMap::value_type& child: children_) {
 | 
			
		||||
    childOrder[child.second->myOrder_] = child.second;
 | 
			
		||||
| 
						 | 
				
			
			@ -141,10 +141,10 @@ void TimingOutline::print2(const std::string& outline,
 | 
			
		|||
}
 | 
			
		||||
 | 
			
		||||
/* ************************************************************************* */
 | 
			
		||||
const boost::shared_ptr<TimingOutline>& TimingOutline::child(size_t child,
 | 
			
		||||
    const std::string& label, const boost::weak_ptr<TimingOutline>& thisPtr) {
 | 
			
		||||
const std::shared_ptr<TimingOutline>& TimingOutline::child(size_t child,
 | 
			
		||||
    const std::string& label, const std::weak_ptr<TimingOutline>& thisPtr) {
 | 
			
		||||
  assert(thisPtr.lock().get() == this);
 | 
			
		||||
  boost::shared_ptr<TimingOutline>& result = children_[child];
 | 
			
		||||
  std::shared_ptr<TimingOutline>& result = children_[child];
 | 
			
		||||
  if (!result) {
 | 
			
		||||
    // Create child if necessary
 | 
			
		||||
    result.reset(new TimingOutline(label, child));
 | 
			
		||||
| 
						 | 
				
			
			@ -236,7 +236,7 @@ size_t getTicTocID(const char *descriptionC) {
 | 
			
		|||
/* ************************************************************************* */
 | 
			
		||||
void tic(size_t id, const char *labelC) {
 | 
			
		||||
  const std::string label(labelC);
 | 
			
		||||
  boost::shared_ptr<TimingOutline> node = //
 | 
			
		||||
  std::shared_ptr<TimingOutline> node = //
 | 
			
		||||
      gCurrentTimer.lock()->child(id, label, gCurrentTimer);
 | 
			
		||||
  gCurrentTimer = node;
 | 
			
		||||
  node->tic();
 | 
			
		||||
| 
						 | 
				
			
			@ -244,7 +244,7 @@ void tic(size_t id, const char *labelC) {
 | 
			
		|||
 | 
			
		||||
/* ************************************************************************* */
 | 
			
		||||
void toc(size_t id, const char *label) {
 | 
			
		||||
  boost::shared_ptr<TimingOutline> current(gCurrentTimer.lock());
 | 
			
		||||
  std::shared_ptr<TimingOutline> current(gCurrentTimer.lock());
 | 
			
		||||
  if (id != current->id_) {
 | 
			
		||||
    gTimingRoot->print();
 | 
			
		||||
    throw std::invalid_argument(
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -21,8 +21,6 @@
 | 
			
		|||
#include <gtsam/dllexport.h>
 | 
			
		||||
#include <gtsam/config.h> // for GTSAM_USE_TBB
 | 
			
		||||
 | 
			
		||||
#include <boost/smart_ptr/shared_ptr.hpp>
 | 
			
		||||
#include <boost/smart_ptr/weak_ptr.hpp>
 | 
			
		||||
#include <boost/version.hpp>
 | 
			
		||||
 | 
			
		||||
#include <cstddef>
 | 
			
		||||
| 
						 | 
				
			
			@ -157,8 +155,8 @@ namespace gtsam {
 | 
			
		|||
      std::string label_;
 | 
			
		||||
 | 
			
		||||
      // Tree structure
 | 
			
		||||
      boost::weak_ptr<TimingOutline> parent_; ///< parent pointer
 | 
			
		||||
      typedef FastMap<size_t, boost::shared_ptr<TimingOutline> > ChildMap;
 | 
			
		||||
      std::weak_ptr<TimingOutline> parent_; ///< parent pointer
 | 
			
		||||
      typedef FastMap<size_t, std::shared_ptr<TimingOutline> > ChildMap;
 | 
			
		||||
      ChildMap children_; ///< subtrees
 | 
			
		||||
 | 
			
		||||
#ifdef GTSAM_USING_NEW_BOOST_TIMERS
 | 
			
		||||
| 
						 | 
				
			
			@ -184,8 +182,8 @@ namespace gtsam {
 | 
			
		|||
      double mean() const { return self() / double(n_); } ///< mean self time, in seconds
 | 
			
		||||
      GTSAM_EXPORT void print(const std::string& outline = "") const;
 | 
			
		||||
      GTSAM_EXPORT void print2(const std::string& outline = "", const double parentTotal = -1.0) const;
 | 
			
		||||
      GTSAM_EXPORT const boost::shared_ptr<TimingOutline>&
 | 
			
		||||
        child(size_t child, const std::string& label, const boost::weak_ptr<TimingOutline>& thisPtr);
 | 
			
		||||
      GTSAM_EXPORT const std::shared_ptr<TimingOutline>&
 | 
			
		||||
        child(size_t child, const std::string& label, const std::weak_ptr<TimingOutline>& thisPtr);
 | 
			
		||||
      GTSAM_EXPORT void tic();
 | 
			
		||||
      GTSAM_EXPORT void toc();
 | 
			
		||||
      GTSAM_EXPORT void finishedIteration();
 | 
			
		||||
| 
						 | 
				
			
			@ -216,8 +214,8 @@ namespace gtsam {
 | 
			
		|||
      }
 | 
			
		||||
    };
 | 
			
		||||
 | 
			
		||||
    GTSAM_EXTERN_EXPORT boost::shared_ptr<TimingOutline> gTimingRoot;
 | 
			
		||||
    GTSAM_EXTERN_EXPORT boost::weak_ptr<TimingOutline> gCurrentTimer;
 | 
			
		||||
    GTSAM_EXTERN_EXPORT std::shared_ptr<TimingOutline> gTimingRoot;
 | 
			
		||||
    GTSAM_EXTERN_EXPORT std::weak_ptr<TimingOutline> gCurrentTimer;
 | 
			
		||||
  }
 | 
			
		||||
 | 
			
		||||
// Tic and toc functions that are always active (whether or not ENABLE_TIMING is defined)
 | 
			
		||||
| 
						 | 
				
			
			@ -260,7 +258,7 @@ inline void tictoc_print2_() {
 | 
			
		|||
// get a node by label and assign it to variable
 | 
			
		||||
#define tictoc_getNode(variable, label) \
 | 
			
		||||
  static const size_t label##_id_getnode = ::gtsam::internal::getTicTocID(#label); \
 | 
			
		||||
  const boost::shared_ptr<const ::gtsam::internal::TimingOutline> variable = \
 | 
			
		||||
  const std::shared_ptr<const ::gtsam::internal::TimingOutline> variable = \
 | 
			
		||||
  ::gtsam::internal::gCurrentTimer.lock()->child(label##_id_getnode, #label, ::gtsam::internal::gCurrentTimer);
 | 
			
		||||
 | 
			
		||||
// reset
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -27,8 +27,7 @@
 | 
			
		|||
#include <stack>
 | 
			
		||||
#include <vector>
 | 
			
		||||
#include <string>
 | 
			
		||||
#include <boost/shared_ptr.hpp>
 | 
			
		||||
#include <boost/make_shared.hpp>
 | 
			
		||||
#include <memory>
 | 
			
		||||
 | 
			
		||||
namespace gtsam {
 | 
			
		||||
 | 
			
		||||
| 
						 | 
				
			
			@ -41,10 +40,10 @@ namespace {
 | 
			
		|||
template<typename NODE, typename DATA>
 | 
			
		||||
struct TraversalNode {
 | 
			
		||||
  bool expanded;
 | 
			
		||||
  const boost::shared_ptr<NODE>& treeNode;
 | 
			
		||||
  const std::shared_ptr<NODE>& treeNode;
 | 
			
		||||
  DATA& parentData;
 | 
			
		||||
  typename FastList<DATA>::iterator dataPointer;
 | 
			
		||||
  TraversalNode(const boost::shared_ptr<NODE>& _treeNode, DATA& _parentData) :
 | 
			
		||||
  TraversalNode(const std::shared_ptr<NODE>& _treeNode, DATA& _parentData) :
 | 
			
		||||
      expanded(false), treeNode(_treeNode), parentData(_parentData) {
 | 
			
		||||
  }
 | 
			
		||||
};
 | 
			
		||||
| 
						 | 
				
			
			@ -52,7 +51,7 @@ struct TraversalNode {
 | 
			
		|||
// Do nothing - default argument for post-visitor for tree traversal
 | 
			
		||||
struct no_op {
 | 
			
		||||
  template<typename NODE, typename DATA>
 | 
			
		||||
  void operator()(const boost::shared_ptr<NODE>& node, const DATA& data) {
 | 
			
		||||
  void operator()(const std::shared_ptr<NODE>& node, const DATA& data) {
 | 
			
		||||
  }
 | 
			
		||||
};
 | 
			
		||||
 | 
			
		||||
| 
						 | 
				
			
			@ -78,7 +77,7 @@ void DepthFirstForest(FOREST& forest, DATA& rootData, VISITOR_PRE& visitorPre,
 | 
			
		|||
    VISITOR_POST& visitorPost) {
 | 
			
		||||
  // Typedefs
 | 
			
		||||
  typedef typename FOREST::Node Node;
 | 
			
		||||
  typedef boost::shared_ptr<Node> sharedNode;
 | 
			
		||||
  typedef std::shared_ptr<Node> sharedNode;
 | 
			
		||||
 | 
			
		||||
  // Depth first traversal stack
 | 
			
		||||
  typedef TraversalNode<typename FOREST::Node, DATA> TraversalNode;
 | 
			
		||||
| 
						 | 
				
			
			@ -169,29 +168,29 @@ void DepthFirstForestParallel(FOREST& forest, DATA& rootData,
 | 
			
		|||
/** Traversal function for CloneForest */
 | 
			
		||||
namespace {
 | 
			
		||||
template<typename NODE>
 | 
			
		||||
boost::shared_ptr<NODE> CloneForestVisitorPre(
 | 
			
		||||
    const boost::shared_ptr<NODE>& node,
 | 
			
		||||
    const boost::shared_ptr<NODE>& parentPointer) {
 | 
			
		||||
std::shared_ptr<NODE> CloneForestVisitorPre(
 | 
			
		||||
    const std::shared_ptr<NODE>& node,
 | 
			
		||||
    const std::shared_ptr<NODE>& parentPointer) {
 | 
			
		||||
  // Clone the current node and add it to its cloned parent
 | 
			
		||||
  boost::shared_ptr<NODE> clone = boost::make_shared<NODE>(*node);
 | 
			
		||||
  std::shared_ptr<NODE> clone = std::make_shared<NODE>(*node);
 | 
			
		||||
  clone->children.clear();
 | 
			
		||||
  parentPointer->children.push_back(clone);
 | 
			
		||||
  return clone;
 | 
			
		||||
}
 | 
			
		||||
}
 | 
			
		||||
 | 
			
		||||
/** Clone a tree, copy-constructing new nodes (calling boost::make_shared) and setting up child
 | 
			
		||||
/** Clone a tree, copy-constructing new nodes (calling std::make_shared) and setting up child
 | 
			
		||||
 *  pointers for a clone of the original tree.
 | 
			
		||||
 *  @param forest The forest of trees to clone.  The method \c forest.roots() should exist and
 | 
			
		||||
 *         return a collection of shared pointers to \c FOREST::Node.
 | 
			
		||||
 *  @return The new collection of roots. */
 | 
			
		||||
template<class FOREST>
 | 
			
		||||
FastVector<boost::shared_ptr<typename FOREST::Node> > CloneForest(
 | 
			
		||||
FastVector<std::shared_ptr<typename FOREST::Node> > CloneForest(
 | 
			
		||||
    const FOREST& forest) {
 | 
			
		||||
  typedef typename FOREST::Node Node;
 | 
			
		||||
  boost::shared_ptr<Node> rootContainer = boost::make_shared<Node>();
 | 
			
		||||
  std::shared_ptr<Node> rootContainer = std::make_shared<Node>();
 | 
			
		||||
  DepthFirstForest(forest, rootContainer, CloneForestVisitorPre<Node>);
 | 
			
		||||
  return FastVector<boost::shared_ptr<Node> >(rootContainer->children.begin(),
 | 
			
		||||
  return FastVector<std::shared_ptr<Node> >(rootContainer->children.begin(),
 | 
			
		||||
      rootContainer->children.end());
 | 
			
		||||
}
 | 
			
		||||
 | 
			
		||||
| 
						 | 
				
			
			@ -204,7 +203,7 @@ struct PrintForestVisitorPre {
 | 
			
		|||
      formatter(formatter) {
 | 
			
		||||
  }
 | 
			
		||||
  template<typename NODE> std::string operator()(
 | 
			
		||||
      const boost::shared_ptr<NODE>& node, const std::string& parentString) {
 | 
			
		||||
      const std::shared_ptr<NODE>& node, const std::string& parentString) {
 | 
			
		||||
    // Print the current node
 | 
			
		||||
    node->print(parentString + "-", formatter);
 | 
			
		||||
    // Increment the indentation
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -18,8 +18,7 @@
 | 
			
		|||
 | 
			
		||||
#include <gtsam/global_includes.h>
 | 
			
		||||
 | 
			
		||||
#include <boost/shared_ptr.hpp>
 | 
			
		||||
#include <boost/make_shared.hpp>
 | 
			
		||||
#include <memory>
 | 
			
		||||
 | 
			
		||||
#ifdef GTSAM_USE_TBB
 | 
			
		||||
#include <tbb/task_group.h>         // tbb::task_group
 | 
			
		||||
| 
						 | 
				
			
			@ -37,8 +36,8 @@ namespace gtsam {
 | 
			
		|||
      class PreOrderTask
 | 
			
		||||
      {
 | 
			
		||||
      public:
 | 
			
		||||
        const boost::shared_ptr<NODE>& treeNode;
 | 
			
		||||
        boost::shared_ptr<DATA> myData;
 | 
			
		||||
        const std::shared_ptr<NODE>& treeNode;
 | 
			
		||||
        std::shared_ptr<DATA> myData;
 | 
			
		||||
        VISITOR_PRE& visitorPre;
 | 
			
		||||
        VISITOR_POST& visitorPost;
 | 
			
		||||
        int problemSizeThreshold;
 | 
			
		||||
| 
						 | 
				
			
			@ -48,7 +47,7 @@ namespace gtsam {
 | 
			
		|||
        // Keep track of order phase across multiple calls to the same functor
 | 
			
		||||
        mutable bool isPostOrderPhase;
 | 
			
		||||
 | 
			
		||||
        PreOrderTask(const boost::shared_ptr<NODE>& treeNode, const boost::shared_ptr<DATA>& myData,
 | 
			
		||||
        PreOrderTask(const std::shared_ptr<NODE>& treeNode, const std::shared_ptr<DATA>& myData,
 | 
			
		||||
                     VISITOR_PRE& visitorPre, VISITOR_POST& visitorPost, int problemSizeThreshold,
 | 
			
		||||
                     tbb::task_group& tg, bool makeNewTasks = true)
 | 
			
		||||
            : treeNode(treeNode),
 | 
			
		||||
| 
						 | 
				
			
			@ -77,12 +76,12 @@ namespace gtsam {
 | 
			
		|||
 | 
			
		||||
                // If we have child tasks, start subtasks and wait for them to complete
 | 
			
		||||
                tbb::task_group ctg;
 | 
			
		||||
                for(const boost::shared_ptr<NODE>& child: treeNode->children)
 | 
			
		||||
                for(const std::shared_ptr<NODE>& child: treeNode->children)
 | 
			
		||||
                {
 | 
			
		||||
                  // Process child in a subtask.  Important:  Run visitorPre before calling
 | 
			
		||||
                  // allocate_child so that if visitorPre throws an exception, we will not have
 | 
			
		||||
                  // allocated an extra child, this causes a TBB error.
 | 
			
		||||
                  boost::shared_ptr<DATA> childData = boost::allocate_shared<DATA>(
 | 
			
		||||
                  std::shared_ptr<DATA> childData = std::allocate_shared<DATA>(
 | 
			
		||||
                      tbb::scalable_allocator<DATA>(), visitorPre(child, *myData));
 | 
			
		||||
                  ctg.run(PreOrderTask(child, childData, visitorPre, visitorPost,
 | 
			
		||||
                      problemSizeThreshold, ctg, overThreshold));
 | 
			
		||||
| 
						 | 
				
			
			@ -107,9 +106,9 @@ namespace gtsam {
 | 
			
		|||
          }
 | 
			
		||||
        }
 | 
			
		||||
 | 
			
		||||
        void processNodeRecursively(const boost::shared_ptr<NODE>& node, DATA& myData) const
 | 
			
		||||
        void processNodeRecursively(const std::shared_ptr<NODE>& node, DATA& myData) const
 | 
			
		||||
        {
 | 
			
		||||
          for(const boost::shared_ptr<NODE>& child: node->children)
 | 
			
		||||
          for(const std::shared_ptr<NODE>& child: node->children)
 | 
			
		||||
          {
 | 
			
		||||
            DATA childData = visitorPre(child, myData);
 | 
			
		||||
            processNodeRecursively(child, childData);
 | 
			
		||||
| 
						 | 
				
			
			@ -140,9 +139,9 @@ namespace gtsam {
 | 
			
		|||
        {
 | 
			
		||||
          typedef PreOrderTask<NODE, DATA, VISITOR_PRE, VISITOR_POST> PreOrderTask;
 | 
			
		||||
          // Create data and tasks for our children
 | 
			
		||||
          for(const boost::shared_ptr<NODE>& root: roots)
 | 
			
		||||
          for(const std::shared_ptr<NODE>& root: roots)
 | 
			
		||||
          {
 | 
			
		||||
            boost::shared_ptr<DATA> rootData = boost::allocate_shared<DATA>(tbb::scalable_allocator<DATA>(), visitorPre(root, myData));
 | 
			
		||||
            std::shared_ptr<DATA> rootData = std::allocate_shared<DATA>(tbb::scalable_allocator<DATA>(), visitorPre(root, myData));
 | 
			
		||||
            tg.run(PreOrderTask(root, rootData, visitorPre, visitorPost, problemSizeThreshold, tg));
 | 
			
		||||
          }
 | 
			
		||||
        }
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -55,7 +55,7 @@ namespace gtsam {
 | 
			
		|||
    /* ************************************************************************* */
 | 
			
		||||
    namespace internal {
 | 
			
		||||
      template<class NODE>
 | 
			
		||||
      ForestStatistics* statisticsVisitor(const boost::shared_ptr<NODE>& node, ForestStatistics* stats)
 | 
			
		||||
      ForestStatistics* statisticsVisitor(const std::shared_ptr<NODE>& node, ForestStatistics* stats)
 | 
			
		||||
      {
 | 
			
		||||
        (*stats->problemSizeHistogram[node->problemSize()]) ++;
 | 
			
		||||
        (*stats->numberOfChildrenHistogram[(int)node->children.size()]) ++;
 | 
			
		||||
| 
						 | 
				
			
			@ -63,7 +63,7 @@ namespace gtsam {
 | 
			
		|||
        {
 | 
			
		||||
          int largestProblemSize = 0;
 | 
			
		||||
          int secondLargestProblemSize = 0;
 | 
			
		||||
          for(const boost::shared_ptr<NODE>& child: node->children)
 | 
			
		||||
          for(const std::shared_ptr<NODE>& child: node->children)
 | 
			
		||||
          {
 | 
			
		||||
            if (child->problemSize() > largestProblemSize)
 | 
			
		||||
            {
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -279,7 +279,7 @@ namespace gtsam {
 | 
			
		|||
  /**
 | 
			
		||||
   * A SFINAE trait to mark classes that need special alignment.
 | 
			
		||||
   *
 | 
			
		||||
   * This is required to make boost::make_shared and etc respect alignment, which is essential for the Python
 | 
			
		||||
   * This is required to make std::make_shared and etc respect alignment, which is essential for the Python
 | 
			
		||||
   * wrappers to work properly.
 | 
			
		||||
   *
 | 
			
		||||
   * Explanation
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -94,7 +94,7 @@ TEST(Basis, Manual) {
 | 
			
		|||
 | 
			
		||||
    auto linearizedFactor = predictFactor.linearize(values);
 | 
			
		||||
    auto linearizedJacobianFactor =
 | 
			
		||||
        boost::dynamic_pointer_cast<JacobianFactor>(linearizedFactor);
 | 
			
		||||
        std::dynamic_pointer_cast<JacobianFactor>(linearizedFactor);
 | 
			
		||||
    CHECK(linearizedJacobianFactor);  // makes sure it's indeed a JacobianFactor
 | 
			
		||||
    EXPECT(assert_equal(linearFactor, *linearizedJacobianFactor, 1e-9));
 | 
			
		||||
  }
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -23,7 +23,6 @@
 | 
			
		|||
 | 
			
		||||
#include <algorithm>
 | 
			
		||||
#include <boost/format.hpp>
 | 
			
		||||
#include <boost/make_shared.hpp>
 | 
			
		||||
 | 
			
		||||
#include <cmath>
 | 
			
		||||
#include <fstream>
 | 
			
		||||
| 
						 | 
				
			
			@ -183,7 +182,7 @@ namespace gtsam {
 | 
			
		|||
     */
 | 
			
		||||
    size_t allSame_;
 | 
			
		||||
 | 
			
		||||
    using ChoicePtr = boost::shared_ptr<const Choice>;
 | 
			
		||||
    using ChoicePtr = std::shared_ptr<const Choice>;
 | 
			
		||||
 | 
			
		||||
   public:
 | 
			
		||||
    /// Default constructor for serialization.
 | 
			
		||||
| 
						 | 
				
			
			@ -207,10 +206,10 @@ namespace gtsam {
 | 
			
		|||
        for(auto branch: f->branches()) {
 | 
			
		||||
          assert(branch->isLeaf());
 | 
			
		||||
          nrAssignments +=
 | 
			
		||||
              boost::dynamic_pointer_cast<const Leaf>(branch)->nrAssignments();
 | 
			
		||||
              std::dynamic_pointer_cast<const Leaf>(branch)->nrAssignments();
 | 
			
		||||
        }
 | 
			
		||||
        NodePtr newLeaf(
 | 
			
		||||
            new Leaf(boost::dynamic_pointer_cast<const Leaf>(f0)->constant(),
 | 
			
		||||
            new Leaf(std::dynamic_pointer_cast<const Leaf>(f0)->constant(),
 | 
			
		||||
                     nrAssignments));
 | 
			
		||||
        return newLeaf;
 | 
			
		||||
      } else
 | 
			
		||||
| 
						 | 
				
			
			@ -387,14 +386,14 @@ namespace gtsam {
 | 
			
		|||
 | 
			
		||||
    /// apply unary operator.
 | 
			
		||||
    NodePtr apply(const Unary& op) const override {
 | 
			
		||||
      auto r = boost::make_shared<Choice>(label_, *this, op);
 | 
			
		||||
      auto r = std::make_shared<Choice>(label_, *this, op);
 | 
			
		||||
      return Unique(r);
 | 
			
		||||
    }
 | 
			
		||||
 | 
			
		||||
    /// Apply unary operator with assignment
 | 
			
		||||
    NodePtr apply(const UnaryAssignment& op,
 | 
			
		||||
                  const Assignment<L>& assignment) const override {
 | 
			
		||||
      auto r = boost::make_shared<Choice>(label_, *this, op, assignment);
 | 
			
		||||
      auto r = std::make_shared<Choice>(label_, *this, op, assignment);
 | 
			
		||||
      return Unique(r);
 | 
			
		||||
    }
 | 
			
		||||
 | 
			
		||||
| 
						 | 
				
			
			@ -409,7 +408,7 @@ namespace gtsam {
 | 
			
		|||
 | 
			
		||||
    // If second argument of binary op is Leaf node, recurse on branches
 | 
			
		||||
    NodePtr apply_g_op_fL(const Leaf& fL, const Binary& op) const override {
 | 
			
		||||
      auto h = boost::make_shared<Choice>(label(), nrChoices());
 | 
			
		||||
      auto h = std::make_shared<Choice>(label(), nrChoices());
 | 
			
		||||
      for (auto&& branch : branches_)
 | 
			
		||||
        h->push_back(fL.apply_f_op_g(*branch, op));
 | 
			
		||||
      return Unique(h);
 | 
			
		||||
| 
						 | 
				
			
			@ -417,14 +416,14 @@ namespace gtsam {
 | 
			
		|||
 | 
			
		||||
    // If second argument of binary op is Choice, call constructor
 | 
			
		||||
    NodePtr apply_g_op_fC(const Choice& fC, const Binary& op) const override {
 | 
			
		||||
      auto h = boost::make_shared<Choice>(fC, *this, op);
 | 
			
		||||
      auto h = std::make_shared<Choice>(fC, *this, op);
 | 
			
		||||
      return Unique(h);
 | 
			
		||||
    }
 | 
			
		||||
 | 
			
		||||
    // If second argument of binary op is Leaf
 | 
			
		||||
    template<typename OP>
 | 
			
		||||
    NodePtr apply_fC_op_gL(const Leaf& gL, OP op) const {
 | 
			
		||||
      auto h = boost::make_shared<Choice>(label(), nrChoices());
 | 
			
		||||
      auto h = std::make_shared<Choice>(label(), nrChoices());
 | 
			
		||||
      for (auto&& branch : branches_)
 | 
			
		||||
        h->push_back(branch->apply_f_op_g(gL, op));
 | 
			
		||||
      return Unique(h);
 | 
			
		||||
| 
						 | 
				
			
			@ -435,7 +434,7 @@ namespace gtsam {
 | 
			
		|||
      if (label_ == label) return branches_[index];  // choose branch
 | 
			
		||||
 | 
			
		||||
      // second case, not label of interest, just recurse
 | 
			
		||||
      auto r = boost::make_shared<Choice>(label_, branches_.size());
 | 
			
		||||
      auto r = std::make_shared<Choice>(label_, branches_.size());
 | 
			
		||||
      for (auto&& branch : branches_)
 | 
			
		||||
        r->push_back(branch->choose(label, index));
 | 
			
		||||
      return Unique(r);
 | 
			
		||||
| 
						 | 
				
			
			@ -476,7 +475,7 @@ namespace gtsam {
 | 
			
		|||
  /****************************************************************************/
 | 
			
		||||
  template <typename L, typename Y>
 | 
			
		||||
  DecisionTree<L, Y>::DecisionTree(const L& label, const Y& y1, const Y& y2) {
 | 
			
		||||
    auto a = boost::make_shared<Choice>(label, 2);
 | 
			
		||||
    auto a = std::make_shared<Choice>(label, 2);
 | 
			
		||||
    NodePtr l1(new Leaf(y1)), l2(new Leaf(y2));
 | 
			
		||||
    a->push_back(l1);
 | 
			
		||||
    a->push_back(l2);
 | 
			
		||||
| 
						 | 
				
			
			@ -489,7 +488,7 @@ namespace gtsam {
 | 
			
		|||
                                   const Y& y2) {
 | 
			
		||||
    if (labelC.second != 2) throw std::invalid_argument(
 | 
			
		||||
        "DecisionTree: binary constructor called with non-binary label");
 | 
			
		||||
    auto a = boost::make_shared<Choice>(labelC.first, 2);
 | 
			
		||||
    auto a = std::make_shared<Choice>(labelC.first, 2);
 | 
			
		||||
    NodePtr l1(new Leaf(y1)), l2(new Leaf(y2));
 | 
			
		||||
    a->push_back(l1);
 | 
			
		||||
    a->push_back(l2);
 | 
			
		||||
| 
						 | 
				
			
			@ -568,8 +567,8 @@ namespace gtsam {
 | 
			
		|||
    for (Iterator it = begin; it != end; it++) {
 | 
			
		||||
      if (it->root_->isLeaf())
 | 
			
		||||
        continue;
 | 
			
		||||
      boost::shared_ptr<const Choice> c =
 | 
			
		||||
          boost::dynamic_pointer_cast<const Choice>(it->root_);
 | 
			
		||||
      std::shared_ptr<const Choice> c =
 | 
			
		||||
          std::dynamic_pointer_cast<const Choice>(it->root_);
 | 
			
		||||
      if (!highestLabel || c->label() > *highestLabel) {
 | 
			
		||||
        highestLabel = c->label();
 | 
			
		||||
        nrChoices = c->nrChoices();
 | 
			
		||||
| 
						 | 
				
			
			@ -578,14 +577,14 @@ namespace gtsam {
 | 
			
		|||
 | 
			
		||||
    // if label is already in correct order, just put together a choice on label
 | 
			
		||||
    if (!nrChoices || !highestLabel || label > *highestLabel) {
 | 
			
		||||
      auto choiceOnLabel = boost::make_shared<Choice>(label, end - begin);
 | 
			
		||||
      auto choiceOnLabel = std::make_shared<Choice>(label, end - begin);
 | 
			
		||||
      for (Iterator it = begin; it != end; it++)
 | 
			
		||||
        choiceOnLabel->push_back(it->root_);
 | 
			
		||||
      return Choice::Unique(choiceOnLabel);
 | 
			
		||||
    } else {
 | 
			
		||||
      // Set up a new choice on the highest label
 | 
			
		||||
      auto choiceOnHighestLabel =
 | 
			
		||||
          boost::make_shared<Choice>(*highestLabel, nrChoices);
 | 
			
		||||
          std::make_shared<Choice>(*highestLabel, nrChoices);
 | 
			
		||||
      // now, for all possible values of highestLabel
 | 
			
		||||
      for (size_t index = 0; index < nrChoices; index++) {
 | 
			
		||||
        // make a new set of functions for composing by iterating over the given
 | 
			
		||||
| 
						 | 
				
			
			@ -647,7 +646,7 @@ namespace gtsam {
 | 
			
		|||
                  << std::endl;
 | 
			
		||||
        throw std::invalid_argument("DecisionTree::create invalid argument");
 | 
			
		||||
      }
 | 
			
		||||
      auto choice = boost::make_shared<Choice>(begin->first, endY - beginY);
 | 
			
		||||
      auto choice = std::make_shared<Choice>(begin->first, endY - beginY);
 | 
			
		||||
      for (ValueIt y = beginY; y != endY; y++)
 | 
			
		||||
        choice->push_back(NodePtr(new Leaf(*y)));
 | 
			
		||||
      return Choice::Unique(choice);
 | 
			
		||||
| 
						 | 
				
			
			@ -678,13 +677,13 @@ namespace gtsam {
 | 
			
		|||
    // functions.
 | 
			
		||||
    // If leaf, apply unary conversion "op" and create a unique leaf.
 | 
			
		||||
    using MXLeaf = typename DecisionTree<M, X>::Leaf;
 | 
			
		||||
    if (auto leaf = boost::dynamic_pointer_cast<const MXLeaf>(f)) {
 | 
			
		||||
    if (auto leaf = std::dynamic_pointer_cast<const MXLeaf>(f)) {
 | 
			
		||||
      return NodePtr(new Leaf(Y_of_X(leaf->constant()), leaf->nrAssignments()));
 | 
			
		||||
    }
 | 
			
		||||
 | 
			
		||||
    // Check if Choice
 | 
			
		||||
    using MXChoice = typename DecisionTree<M, X>::Choice;
 | 
			
		||||
    auto choice = boost::dynamic_pointer_cast<const MXChoice>(f);
 | 
			
		||||
    auto choice = std::dynamic_pointer_cast<const MXChoice>(f);
 | 
			
		||||
    if (!choice) throw std::invalid_argument(
 | 
			
		||||
        "DecisionTree::convertFrom: Invalid NodePtr");
 | 
			
		||||
 | 
			
		||||
| 
						 | 
				
			
			@ -720,11 +719,11 @@ namespace gtsam {
 | 
			
		|||
    /// Do a depth-first visit on the tree rooted at node.
 | 
			
		||||
    void operator()(const typename DecisionTree<L, Y>::NodePtr& node) const {
 | 
			
		||||
      using Leaf = typename DecisionTree<L, Y>::Leaf;
 | 
			
		||||
      if (auto leaf = boost::dynamic_pointer_cast<const Leaf>(node))
 | 
			
		||||
      if (auto leaf = std::dynamic_pointer_cast<const Leaf>(node))
 | 
			
		||||
        return f(leaf->constant());
 | 
			
		||||
 | 
			
		||||
      using Choice = typename DecisionTree<L, Y>::Choice;
 | 
			
		||||
      auto choice = boost::dynamic_pointer_cast<const Choice>(node);
 | 
			
		||||
      auto choice = std::dynamic_pointer_cast<const Choice>(node);
 | 
			
		||||
      if (!choice)
 | 
			
		||||
        throw std::invalid_argument("DecisionTree::Visit: Invalid NodePtr");
 | 
			
		||||
      for (auto&& branch : choice->branches()) (*this)(branch);  // recurse!
 | 
			
		||||
| 
						 | 
				
			
			@ -757,11 +756,11 @@ namespace gtsam {
 | 
			
		|||
    /// Do a depth-first visit on the tree rooted at node.
 | 
			
		||||
    void operator()(const typename DecisionTree<L, Y>::NodePtr& node) const {
 | 
			
		||||
      using Leaf = typename DecisionTree<L, Y>::Leaf;
 | 
			
		||||
      if (auto leaf = boost::dynamic_pointer_cast<const Leaf>(node))
 | 
			
		||||
      if (auto leaf = std::dynamic_pointer_cast<const Leaf>(node))
 | 
			
		||||
        return f(*leaf);
 | 
			
		||||
 | 
			
		||||
      using Choice = typename DecisionTree<L, Y>::Choice;
 | 
			
		||||
      auto choice = boost::dynamic_pointer_cast<const Choice>(node);
 | 
			
		||||
      auto choice = std::dynamic_pointer_cast<const Choice>(node);
 | 
			
		||||
      if (!choice)
 | 
			
		||||
        throw std::invalid_argument("DecisionTree::VisitLeaf: Invalid NodePtr");
 | 
			
		||||
      for (auto&& branch : choice->branches()) (*this)(branch);  // recurse!
 | 
			
		||||
| 
						 | 
				
			
			@ -792,11 +791,11 @@ namespace gtsam {
 | 
			
		|||
    /// Do a depth-first visit on the tree rooted at node.
 | 
			
		||||
    void operator()(const typename DecisionTree<L, Y>::NodePtr& node) {
 | 
			
		||||
      using Leaf = typename DecisionTree<L, Y>::Leaf;
 | 
			
		||||
      if (auto leaf = boost::dynamic_pointer_cast<const Leaf>(node))
 | 
			
		||||
      if (auto leaf = std::dynamic_pointer_cast<const Leaf>(node))
 | 
			
		||||
        return f(assignment, leaf->constant());
 | 
			
		||||
 | 
			
		||||
      using Choice = typename DecisionTree<L, Y>::Choice;
 | 
			
		||||
      auto choice = boost::dynamic_pointer_cast<const Choice>(node);
 | 
			
		||||
      auto choice = std::dynamic_pointer_cast<const Choice>(node);
 | 
			
		||||
      if (!choice)
 | 
			
		||||
        throw std::invalid_argument("DecisionTree::VisitWith: Invalid NodePtr");
 | 
			
		||||
      for (size_t i = 0; i < choice->nrChoices(); i++) {
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -24,7 +24,7 @@
 | 
			
		|||
#include <gtsam/discrete/Assignment.h>
 | 
			
		||||
 | 
			
		||||
#include <boost/serialization/nvp.hpp>
 | 
			
		||||
#include <boost/shared_ptr.hpp>
 | 
			
		||||
#include <memory>
 | 
			
		||||
#include <functional>
 | 
			
		||||
#include <iostream>
 | 
			
		||||
#include <map>
 | 
			
		||||
| 
						 | 
				
			
			@ -70,7 +70,7 @@ namespace gtsam {
 | 
			
		|||
 | 
			
		||||
    /** ------------------------ Node base class --------------------------- */
 | 
			
		||||
    struct Node {
 | 
			
		||||
      using Ptr = boost::shared_ptr<const Node>;
 | 
			
		||||
      using Ptr = std::shared_ptr<const Node>;
 | 
			
		||||
 | 
			
		||||
#ifdef DT_DEBUG_MEMORY
 | 
			
		||||
      static int nrNodes;
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -22,7 +22,6 @@
 | 
			
		|||
#include <gtsam/discrete/DecisionTreeFactor.h>
 | 
			
		||||
#include <gtsam/discrete/DiscreteConditional.h>
 | 
			
		||||
 | 
			
		||||
#include <boost/make_shared.hpp>
 | 
			
		||||
#include <boost/format.hpp>
 | 
			
		||||
#include <utility>
 | 
			
		||||
 | 
			
		||||
| 
						 | 
				
			
			@ -127,7 +126,7 @@ namespace gtsam {
 | 
			
		|||
      Key j = keys()[i];
 | 
			
		||||
      dkeys.push_back(DiscreteKey(j, cardinality(j)));
 | 
			
		||||
    }
 | 
			
		||||
    return boost::make_shared<DecisionTreeFactor>(dkeys, result);
 | 
			
		||||
    return std::make_shared<DecisionTreeFactor>(dkeys, result);
 | 
			
		||||
  }
 | 
			
		||||
 | 
			
		||||
  /* ************************************************************************ */
 | 
			
		||||
| 
						 | 
				
			
			@ -160,7 +159,7 @@ namespace gtsam {
 | 
			
		|||
        continue;
 | 
			
		||||
      dkeys.push_back(DiscreteKey(j, cardinality(j)));
 | 
			
		||||
    }
 | 
			
		||||
    return boost::make_shared<DecisionTreeFactor>(dkeys, result);
 | 
			
		||||
    return std::make_shared<DecisionTreeFactor>(dkeys, result);
 | 
			
		||||
  }
 | 
			
		||||
 | 
			
		||||
  /* ************************************************************************ */
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -24,7 +24,7 @@
 | 
			
		|||
#include <gtsam/inference/Ordering.h>
 | 
			
		||||
 | 
			
		||||
#include <algorithm>
 | 
			
		||||
#include <boost/shared_ptr.hpp>
 | 
			
		||||
#include <memory>
 | 
			
		||||
#include <map>
 | 
			
		||||
#include <stdexcept>
 | 
			
		||||
#include <string>
 | 
			
		||||
| 
						 | 
				
			
			@ -47,7 +47,7 @@ namespace gtsam {
 | 
			
		|||
    // typedefs needed to play nice with gtsam
 | 
			
		||||
    typedef DecisionTreeFactor This;
 | 
			
		||||
    typedef DiscreteFactor Base;  ///< Typedef to base class
 | 
			
		||||
    typedef boost::shared_ptr<DecisionTreeFactor> shared_ptr;
 | 
			
		||||
    typedef std::shared_ptr<DecisionTreeFactor> shared_ptr;
 | 
			
		||||
    typedef AlgebraicDecisionTree<Key> ADT;
 | 
			
		||||
 | 
			
		||||
   protected:
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -20,7 +20,6 @@
 | 
			
		|||
#include <gtsam/discrete/DiscreteConditional.h>
 | 
			
		||||
#include <gtsam/inference/FactorGraph-inst.h>
 | 
			
		||||
 | 
			
		||||
#include <boost/make_shared.hpp>
 | 
			
		||||
#include <boost/range/adaptor/reversed.hpp>
 | 
			
		||||
 | 
			
		||||
namespace gtsam {
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -23,7 +23,7 @@
 | 
			
		|||
#include <gtsam/inference/BayesNet.h>
 | 
			
		||||
#include <gtsam/inference/FactorGraph.h>
 | 
			
		||||
 | 
			
		||||
#include <boost/shared_ptr.hpp>
 | 
			
		||||
#include <memory>
 | 
			
		||||
#include <map>
 | 
			
		||||
#include <string>
 | 
			
		||||
#include <utility>
 | 
			
		||||
| 
						 | 
				
			
			@ -40,8 +40,8 @@ class GTSAM_EXPORT DiscreteBayesNet: public BayesNet<DiscreteConditional> {
 | 
			
		|||
    typedef BayesNet<DiscreteConditional> Base;
 | 
			
		||||
    typedef DiscreteBayesNet This;
 | 
			
		||||
    typedef DiscreteConditional ConditionalType;
 | 
			
		||||
    typedef boost::shared_ptr<This> shared_ptr;
 | 
			
		||||
    typedef boost::shared_ptr<ConditionalType> sharedConditional;
 | 
			
		||||
    typedef std::shared_ptr<This> shared_ptr;
 | 
			
		||||
    typedef std::shared_ptr<ConditionalType> sharedConditional;
 | 
			
		||||
 | 
			
		||||
    /// @name Standard Constructors
 | 
			
		||||
    /// @{
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -42,12 +42,12 @@ class GTSAM_EXPORT DiscreteBayesTreeClique
 | 
			
		|||
  typedef DiscreteBayesTreeClique This;
 | 
			
		||||
  typedef BayesTreeCliqueBase<DiscreteBayesTreeClique, DiscreteFactorGraph>
 | 
			
		||||
      Base;
 | 
			
		||||
  typedef boost::shared_ptr<This> shared_ptr;
 | 
			
		||||
  typedef boost::weak_ptr<This> weak_ptr;
 | 
			
		||||
  typedef std::shared_ptr<This> shared_ptr;
 | 
			
		||||
  typedef std::weak_ptr<This> weak_ptr;
 | 
			
		||||
  DiscreteBayesTreeClique() {}
 | 
			
		||||
  virtual ~DiscreteBayesTreeClique() {}
 | 
			
		||||
  DiscreteBayesTreeClique(
 | 
			
		||||
      const boost::shared_ptr<DiscreteConditional>& conditional)
 | 
			
		||||
      const std::shared_ptr<DiscreteConditional>& conditional)
 | 
			
		||||
      : Base(conditional) {}
 | 
			
		||||
 | 
			
		||||
  /// print index signature only
 | 
			
		||||
| 
						 | 
				
			
			@ -73,7 +73,7 @@ class GTSAM_EXPORT DiscreteBayesTree
 | 
			
		|||
 | 
			
		||||
 public:
 | 
			
		||||
  typedef DiscreteBayesTree This;
 | 
			
		||||
  typedef boost::shared_ptr<This> shared_ptr;
 | 
			
		||||
  typedef std::shared_ptr<This> shared_ptr;
 | 
			
		||||
 | 
			
		||||
  /// @name Standard interface
 | 
			
		||||
  /// @{
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -23,7 +23,6 @@
 | 
			
		|||
#include <gtsam/hybrid/HybridValues.h>
 | 
			
		||||
 | 
			
		||||
#include <algorithm>
 | 
			
		||||
#include <boost/make_shared.hpp>
 | 
			
		||||
#include <random>
 | 
			
		||||
#include <set>
 | 
			
		||||
#include <stdexcept>
 | 
			
		||||
| 
						 | 
				
			
			@ -195,7 +194,7 @@ DiscreteConditional::shared_ptr DiscreteConditional::choose(
 | 
			
		|||
      dKeys.emplace_back(j, this->cardinality(j));
 | 
			
		||||
    }
 | 
			
		||||
  }
 | 
			
		||||
  return boost::make_shared<DiscreteConditional>(nrFrontals(), dKeys, adt);
 | 
			
		||||
  return std::make_shared<DiscreteConditional>(nrFrontals(), dKeys, adt);
 | 
			
		||||
}
 | 
			
		||||
 | 
			
		||||
/* ************************************************************************** */
 | 
			
		||||
| 
						 | 
				
			
			@ -220,7 +219,7 @@ DecisionTreeFactor::shared_ptr DiscreteConditional::likelihood(
 | 
			
		|||
  for (Key j : parents()) {
 | 
			
		||||
    discreteKeys.emplace_back(j, this->cardinality(j));
 | 
			
		||||
  }
 | 
			
		||||
  return boost::make_shared<DecisionTreeFactor>(discreteKeys, adt);
 | 
			
		||||
  return std::make_shared<DecisionTreeFactor>(discreteKeys, adt);
 | 
			
		||||
}
 | 
			
		||||
 | 
			
		||||
/* ****************************************************************************/
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -22,8 +22,7 @@
 | 
			
		|||
#include <gtsam/discrete/DecisionTreeFactor.h>
 | 
			
		||||
#include <gtsam/discrete/Signature.h>
 | 
			
		||||
 | 
			
		||||
#include <boost/make_shared.hpp>
 | 
			
		||||
#include <boost/shared_ptr.hpp>
 | 
			
		||||
#include <memory>
 | 
			
		||||
#include <string>
 | 
			
		||||
#include <vector>
 | 
			
		||||
 | 
			
		||||
| 
						 | 
				
			
			@ -41,7 +40,7 @@ class GTSAM_EXPORT DiscreteConditional
 | 
			
		|||
 public:
 | 
			
		||||
  // typedefs needed to play nice with gtsam
 | 
			
		||||
  typedef DiscreteConditional This;            ///< Typedef to this class
 | 
			
		||||
  typedef boost::shared_ptr<This> shared_ptr;  ///< shared_ptr to this class
 | 
			
		||||
  typedef std::shared_ptr<This> shared_ptr;  ///< shared_ptr to this class
 | 
			
		||||
  typedef DecisionTreeFactor BaseFactor;  ///< Typedef to our factor base class
 | 
			
		||||
  typedef Conditional<BaseFactor, This>
 | 
			
		||||
      BaseConditional;  ///< Typedef to our conditional base class
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -34,7 +34,7 @@ namespace gtsam {
 | 
			
		|||
  public:
 | 
			
		||||
    typedef EliminationTree<DiscreteBayesNet, DiscreteFactorGraph> Base; ///< Base class
 | 
			
		||||
    typedef DiscreteEliminationTree This; ///< This class
 | 
			
		||||
    typedef boost::shared_ptr<This> shared_ptr; ///< Shared pointer to this class
 | 
			
		||||
    typedef std::shared_ptr<This> shared_ptr; ///< Shared pointer to this class
 | 
			
		||||
 | 
			
		||||
    /**
 | 
			
		||||
    * Build the elimination tree of a factor graph using pre-computed column structure.
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -41,7 +41,7 @@ public:
 | 
			
		|||
 | 
			
		||||
  // typedefs needed to play nice with gtsam
 | 
			
		||||
  typedef DiscreteFactor This; ///< This class
 | 
			
		||||
  typedef boost::shared_ptr<DiscreteFactor> shared_ptr; ///< shared_ptr to this class
 | 
			
		||||
  typedef std::shared_ptr<DiscreteFactor> shared_ptr; ///< shared_ptr to this class
 | 
			
		||||
  typedef Factor Base; ///< Our base class
 | 
			
		||||
 | 
			
		||||
  using Values = DiscreteValues; ///< backwards compatibility
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -54,7 +54,7 @@ namespace gtsam {
 | 
			
		|||
  DiscreteKeys DiscreteFactorGraph::discreteKeys() const {
 | 
			
		||||
    DiscreteKeys result;
 | 
			
		||||
    for (auto&& factor : *this) {
 | 
			
		||||
      if (auto p = boost::dynamic_pointer_cast<DecisionTreeFactor>(factor)) {
 | 
			
		||||
      if (auto p = std::dynamic_pointer_cast<DecisionTreeFactor>(factor)) {
 | 
			
		||||
        DiscreteKeys factor_keys = p->discreteKeys();
 | 
			
		||||
        result.insert(result.end(), factor_keys.begin(), factor_keys.end());
 | 
			
		||||
      }
 | 
			
		||||
| 
						 | 
				
			
			@ -136,12 +136,12 @@ namespace gtsam {
 | 
			
		|||
    // Make lookup with product
 | 
			
		||||
    gttic(lookup);
 | 
			
		||||
    size_t nrFrontals = frontalKeys.size();
 | 
			
		||||
    auto lookup = boost::make_shared<DiscreteLookupTable>(nrFrontals,
 | 
			
		||||
    auto lookup = std::make_shared<DiscreteLookupTable>(nrFrontals,
 | 
			
		||||
                                                          orderedKeys, product);
 | 
			
		||||
    gttoc(lookup);
 | 
			
		||||
 | 
			
		||||
    return std::make_pair(
 | 
			
		||||
        boost::dynamic_pointer_cast<DiscreteConditional>(lookup), max);
 | 
			
		||||
        std::dynamic_pointer_cast<DiscreteConditional>(lookup), max);
 | 
			
		||||
  }
 | 
			
		||||
 | 
			
		||||
  /* ************************************************************************ */
 | 
			
		||||
| 
						 | 
				
			
			@ -220,7 +220,7 @@ namespace gtsam {
 | 
			
		|||
    // now divide product/sum to get conditional
 | 
			
		||||
    gttic(divide);
 | 
			
		||||
    auto conditional =
 | 
			
		||||
        boost::make_shared<DiscreteConditional>(product, *sum, orderedKeys);
 | 
			
		||||
        std::make_shared<DiscreteConditional>(product, *sum, orderedKeys);
 | 
			
		||||
    gttoc(divide);
 | 
			
		||||
 | 
			
		||||
    return std::make_pair(conditional, sum);
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -25,7 +25,6 @@
 | 
			
		|||
#include <gtsam/inference/Ordering.h>
 | 
			
		||||
#include <gtsam/base/FastSet.h>
 | 
			
		||||
 | 
			
		||||
#include <boost/make_shared.hpp>
 | 
			
		||||
#include <string>
 | 
			
		||||
#include <utility>
 | 
			
		||||
#include <vector>
 | 
			
		||||
| 
						 | 
				
			
			@ -48,7 +47,7 @@ class DiscreteJunctionTree;
 | 
			
		|||
 * @return GTSAM_EXPORT
 | 
			
		||||
 * @ingroup discrete
 | 
			
		||||
 */
 | 
			
		||||
GTSAM_EXPORT std::pair<boost::shared_ptr<DiscreteConditional>, DecisionTreeFactor::shared_ptr>
 | 
			
		||||
GTSAM_EXPORT std::pair<std::shared_ptr<DiscreteConditional>, DecisionTreeFactor::shared_ptr>
 | 
			
		||||
EliminateDiscrete(const DiscreteFactorGraph& factors, const Ordering& keys);
 | 
			
		||||
 | 
			
		||||
/* ************************************************************************* */
 | 
			
		||||
| 
						 | 
				
			
			@ -62,8 +61,8 @@ template<> struct EliminationTraits<DiscreteFactorGraph>
 | 
			
		|||
  typedef DiscreteBayesTree BayesTreeType;             ///< Type of Bayes tree
 | 
			
		||||
  typedef DiscreteJunctionTree JunctionTreeType;       ///< Type of Junction tree
 | 
			
		||||
  /// The default dense elimination function
 | 
			
		||||
  static std::pair<boost::shared_ptr<ConditionalType>,
 | 
			
		||||
                   boost::shared_ptr<FactorType> >
 | 
			
		||||
  static std::pair<std::shared_ptr<ConditionalType>,
 | 
			
		||||
                   std::shared_ptr<FactorType> >
 | 
			
		||||
  DefaultEliminate(const FactorGraphType& factors, const Ordering& keys) {
 | 
			
		||||
    return EliminateDiscrete(factors, keys);
 | 
			
		||||
  }
 | 
			
		||||
| 
						 | 
				
			
			@ -89,7 +88,7 @@ class GTSAM_EXPORT DiscreteFactorGraph
 | 
			
		|||
  using Base = FactorGraph<DiscreteFactor>;  ///< base factor graph type
 | 
			
		||||
  using BaseEliminateable =
 | 
			
		||||
      EliminateableFactorGraph<This>;          ///< for elimination
 | 
			
		||||
  using shared_ptr = boost::shared_ptr<This>;  ///< shared_ptr to This
 | 
			
		||||
  using shared_ptr = std::shared_ptr<This>;  ///< shared_ptr to This
 | 
			
		||||
 | 
			
		||||
  using Values = DiscreteValues;  ///< backwards compatibility
 | 
			
		||||
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -53,7 +53,7 @@ namespace gtsam {
 | 
			
		|||
  public:
 | 
			
		||||
    typedef JunctionTree<DiscreteBayesTree, DiscreteFactorGraph> Base; ///< Base class
 | 
			
		||||
    typedef DiscreteJunctionTree This; ///< This class
 | 
			
		||||
    typedef boost::shared_ptr<This> shared_ptr; ///< Shared pointer to this class
 | 
			
		||||
    typedef std::shared_ptr<This> shared_ptr; ///< Shared pointer to this class
 | 
			
		||||
 | 
			
		||||
    /**
 | 
			
		||||
    * Build the elimination tree of a factor graph using precomputed column structure.
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -106,7 +106,7 @@ DiscreteLookupDAG DiscreteLookupDAG::FromBayesNet(
 | 
			
		|||
  DiscreteLookupDAG dag;
 | 
			
		||||
  for (auto&& conditional : bayesNet) {
 | 
			
		||||
    if (auto lookupTable =
 | 
			
		||||
            boost::dynamic_pointer_cast<DiscreteLookupTable>(conditional)) {
 | 
			
		||||
            std::dynamic_pointer_cast<DiscreteLookupTable>(conditional)) {
 | 
			
		||||
      dag.push_back(lookupTable);
 | 
			
		||||
    } else {
 | 
			
		||||
      throw std::runtime_error(
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -21,7 +21,7 @@
 | 
			
		|||
#include <gtsam/inference/BayesNet.h>
 | 
			
		||||
#include <gtsam/inference/FactorGraph.h>
 | 
			
		||||
 | 
			
		||||
#include <boost/shared_ptr.hpp>
 | 
			
		||||
#include <memory>
 | 
			
		||||
#include <string>
 | 
			
		||||
#include <utility>
 | 
			
		||||
#include <vector>
 | 
			
		||||
| 
						 | 
				
			
			@ -40,7 +40,7 @@ class DiscreteBayesNet;
 | 
			
		|||
class GTSAM_EXPORT DiscreteLookupTable : public DiscreteConditional {
 | 
			
		||||
 public:
 | 
			
		||||
  using This = DiscreteLookupTable;
 | 
			
		||||
  using shared_ptr = boost::shared_ptr<This>;
 | 
			
		||||
  using shared_ptr = std::shared_ptr<This>;
 | 
			
		||||
  using BaseConditional = Conditional<DecisionTreeFactor, This>;
 | 
			
		||||
 | 
			
		||||
  /**
 | 
			
		||||
| 
						 | 
				
			
			@ -78,7 +78,7 @@ class GTSAM_EXPORT DiscreteLookupDAG : public BayesNet<DiscreteLookupTable> {
 | 
			
		|||
 public:
 | 
			
		||||
  using Base = BayesNet<DiscreteLookupTable>;
 | 
			
		||||
  using This = DiscreteLookupDAG;
 | 
			
		||||
  using shared_ptr = boost::shared_ptr<This>;
 | 
			
		||||
  using shared_ptr = std::shared_ptr<This>;
 | 
			
		||||
 | 
			
		||||
  /// @name Standard Constructors
 | 
			
		||||
  /// @{
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -326,7 +326,7 @@ TEST(DecisionTree, NrAssignments) {
 | 
			
		|||
  const std::pair<string, size_t> A("A", 2), B("B", 2), C("C", 2);
 | 
			
		||||
  DT tree({A, B, C}, "1 1 1 1 1 1 1 1");
 | 
			
		||||
  EXPECT(tree.root_->isLeaf());
 | 
			
		||||
  auto leaf = boost::dynamic_pointer_cast<const DT::Leaf>(tree.root_);
 | 
			
		||||
  auto leaf = std::dynamic_pointer_cast<const DT::Leaf>(tree.root_);
 | 
			
		||||
  EXPECT_LONGS_EQUAL(8, leaf->nrAssignments());
 | 
			
		||||
 | 
			
		||||
  DT tree2({C, B, A}, "1 1 1 2 3 4 5 5");
 | 
			
		||||
| 
						 | 
				
			
			@ -344,20 +344,20 @@ TEST(DecisionTree, NrAssignments) {
 | 
			
		|||
    1 1 Leaf 5
 | 
			
		||||
  */
 | 
			
		||||
 | 
			
		||||
  auto root = boost::dynamic_pointer_cast<const DT::Choice>(tree2.root_);
 | 
			
		||||
  auto root = std::dynamic_pointer_cast<const DT::Choice>(tree2.root_);
 | 
			
		||||
  CHECK(root);
 | 
			
		||||
  auto choice0 = boost::dynamic_pointer_cast<const DT::Choice>(root->branches()[0]);
 | 
			
		||||
  auto choice0 = std::dynamic_pointer_cast<const DT::Choice>(root->branches()[0]);
 | 
			
		||||
  CHECK(choice0);
 | 
			
		||||
  EXPECT(choice0->branches()[0]->isLeaf());
 | 
			
		||||
  auto choice00 = boost::dynamic_pointer_cast<const DT::Leaf>(choice0->branches()[0]);
 | 
			
		||||
  auto choice00 = std::dynamic_pointer_cast<const DT::Leaf>(choice0->branches()[0]);
 | 
			
		||||
  CHECK(choice00);
 | 
			
		||||
  EXPECT_LONGS_EQUAL(2, choice00->nrAssignments());
 | 
			
		||||
 | 
			
		||||
  auto choice1 = boost::dynamic_pointer_cast<const DT::Choice>(root->branches()[1]);
 | 
			
		||||
  auto choice1 = std::dynamic_pointer_cast<const DT::Choice>(root->branches()[1]);
 | 
			
		||||
  CHECK(choice1);
 | 
			
		||||
  auto choice10 = boost::dynamic_pointer_cast<const DT::Choice>(choice1->branches()[0]);
 | 
			
		||||
  auto choice10 = std::dynamic_pointer_cast<const DT::Choice>(choice1->branches()[0]);
 | 
			
		||||
  CHECK(choice10);
 | 
			
		||||
  auto choice11 = boost::dynamic_pointer_cast<const DT::Leaf>(choice1->branches()[1]);
 | 
			
		||||
  auto choice11 = std::dynamic_pointer_cast<const DT::Leaf>(choice1->branches()[1]);
 | 
			
		||||
  CHECK(choice11);
 | 
			
		||||
  EXPECT(choice11->isLeaf());
 | 
			
		||||
  EXPECT_LONGS_EQUAL(2, choice11->nrAssignments());
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -42,13 +42,13 @@ TEST(DiscreteBayesNet, bayesNet) {
 | 
			
		|||
  DiscreteBayesNet bayesNet;
 | 
			
		||||
  DiscreteKey Parent(0, 2), Child(1, 2);
 | 
			
		||||
 | 
			
		||||
  auto prior = boost::make_shared<DiscreteConditional>(Parent % "6/4");
 | 
			
		||||
  auto prior = std::make_shared<DiscreteConditional>(Parent % "6/4");
 | 
			
		||||
  CHECK(assert_equal(ADT({Parent}, "0.6 0.4"),
 | 
			
		||||
                     (ADT)*prior));
 | 
			
		||||
  bayesNet.push_back(prior);
 | 
			
		||||
 | 
			
		||||
  auto conditional =
 | 
			
		||||
      boost::make_shared<DiscreteConditional>(Child | Parent = "7/3 8/2");
 | 
			
		||||
      std::make_shared<DiscreteConditional>(Child | Parent = "7/3 8/2");
 | 
			
		||||
  EXPECT_LONGS_EQUAL(1, *(conditional->beginFrontals()));
 | 
			
		||||
  ADT expected(Child & Parent, "0.7 0.8 0.3 0.2");
 | 
			
		||||
  CHECK(assert_equal(expected, (ADT)*conditional));
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -34,7 +34,7 @@ static constexpr bool debug = false;
 | 
			
		|||
struct TestFixture {
 | 
			
		||||
  vector<DiscreteKey> keys;
 | 
			
		||||
  DiscreteBayesNet bayesNet;
 | 
			
		||||
  boost::shared_ptr<DiscreteBayesTree> bayesTree;
 | 
			
		||||
  std::shared_ptr<DiscreteBayesTree> bayesTree;
 | 
			
		||||
 | 
			
		||||
  /**
 | 
			
		||||
   * Create a thin-tree Bayesnet, a la Jean-Guillaume Durand (former student),
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -23,7 +23,6 @@
 | 
			
		|||
#include <gtsam/discrete/DiscreteConditional.h>
 | 
			
		||||
#include <gtsam/inference/Symbol.h>
 | 
			
		||||
 | 
			
		||||
#include <boost/make_shared.hpp>
 | 
			
		||||
 | 
			
		||||
using namespace std;
 | 
			
		||||
using namespace gtsam;
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -119,11 +119,11 @@ TEST_UNSAFE( DiscreteMarginals, truss ) {
 | 
			
		|||
//  bayesTree->print("Bayes Tree");
 | 
			
		||||
  typedef DiscreteBayesTreeClique Clique;
 | 
			
		||||
 | 
			
		||||
  Clique expected0(boost::make_shared<DiscreteConditional>((key[0] | key[2], key[4]) = "2/1 2/1 2/1 2/1"));
 | 
			
		||||
  Clique expected0(std::make_shared<DiscreteConditional>((key[0] | key[2], key[4]) = "2/1 2/1 2/1 2/1"));
 | 
			
		||||
  Clique::shared_ptr actual0 = (*bayesTree)[0];
 | 
			
		||||
//  EXPECT(assert_equal(expected0, *actual0)); // TODO, correct but fails
 | 
			
		||||
 | 
			
		||||
  Clique expected1(boost::make_shared<DiscreteConditional>((key[1] | key[3], key[4]) = "1/2 1/2 1/2 1/2"));
 | 
			
		||||
  Clique expected1(std::make_shared<DiscreteConditional>((key[1] | key[3], key[4]) = "1/2 1/2 1/2 1/2"));
 | 
			
		||||
  Clique::shared_ptr actual1 = (*bayesTree)[1];
 | 
			
		||||
//  EXPECT(assert_equal(expected1, *actual1)); // TODO, correct but fails
 | 
			
		||||
 | 
			
		||||
| 
						 | 
				
			
			@ -133,12 +133,12 @@ TEST_UNSAFE( DiscreteMarginals, truss ) {
 | 
			
		|||
  // test 0
 | 
			
		||||
  DecisionTreeFactor expectedM0(key[0],"0.666667 0.333333");
 | 
			
		||||
  DiscreteFactor::shared_ptr actualM0 = marginals(0);
 | 
			
		||||
  EXPECT(assert_equal(expectedM0, *boost::dynamic_pointer_cast<DecisionTreeFactor>(actualM0),1e-5));
 | 
			
		||||
  EXPECT(assert_equal(expectedM0, *std::dynamic_pointer_cast<DecisionTreeFactor>(actualM0),1e-5));
 | 
			
		||||
 | 
			
		||||
  // test 1
 | 
			
		||||
  DecisionTreeFactor expectedM1(key[1],"0.333333 0.666667");
 | 
			
		||||
  DiscreteFactor::shared_ptr actualM1 = marginals(1);
 | 
			
		||||
  EXPECT(assert_equal(expectedM1, *boost::dynamic_pointer_cast<DecisionTreeFactor>(actualM1),1e-5));
 | 
			
		||||
  EXPECT(assert_equal(expectedM1, *std::dynamic_pointer_cast<DecisionTreeFactor>(actualM1),1e-5));
 | 
			
		||||
}
 | 
			
		||||
 | 
			
		||||
/* ************************************************************************* */
 | 
			
		||||
| 
						 | 
				
			
			@ -187,7 +187,7 @@ TEST_UNSAFE(DiscreteMarginals, truss2) {
 | 
			
		|||
    DecisionTreeFactor expectedM(key[j], table);
 | 
			
		||||
    DiscreteFactor::shared_ptr actualM = marginals(j);
 | 
			
		||||
    EXPECT(assert_equal(
 | 
			
		||||
        expectedM, *boost::dynamic_pointer_cast<DecisionTreeFactor>(actualM)));
 | 
			
		||||
        expectedM, *std::dynamic_pointer_cast<DecisionTreeFactor>(actualM)));
 | 
			
		||||
  }
 | 
			
		||||
}
 | 
			
		||||
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -75,7 +75,7 @@ class GTSAM_EXPORT Cal3 {
 | 
			
		|||
 public:
 | 
			
		||||
  enum { dimension = 5 };
 | 
			
		||||
  ///< shared pointer to calibration object
 | 
			
		||||
  using shared_ptr = boost::shared_ptr<Cal3>;
 | 
			
		||||
  using shared_ptr = std::shared_ptr<Cal3>;
 | 
			
		||||
 | 
			
		||||
  /// @name Standard Constructors
 | 
			
		||||
  /// @{
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -42,7 +42,7 @@ class GTSAM_EXPORT Cal3Bundler : public Cal3 {
 | 
			
		|||
  enum { dimension = 3 };
 | 
			
		||||
 | 
			
		||||
  ///< shared pointer to stereo calibration object
 | 
			
		||||
  using shared_ptr = boost::shared_ptr<Cal3Bundler>;
 | 
			
		||||
  using shared_ptr = std::shared_ptr<Cal3Bundler>;
 | 
			
		||||
 | 
			
		||||
  /// @name Standard Constructors
 | 
			
		||||
  /// @{
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -21,7 +21,7 @@
 | 
			
		|||
#pragma once
 | 
			
		||||
 | 
			
		||||
#include <gtsam/geometry/Cal3DS2_Base.h>
 | 
			
		||||
#include <boost/shared_ptr.hpp>
 | 
			
		||||
#include <memory>
 | 
			
		||||
 | 
			
		||||
namespace gtsam {
 | 
			
		||||
 | 
			
		||||
| 
						 | 
				
			
			@ -39,7 +39,7 @@ class GTSAM_EXPORT Cal3DS2 : public Cal3DS2_Base {
 | 
			
		|||
  enum { dimension = 9 };
 | 
			
		||||
 | 
			
		||||
  ///< shared pointer to stereo calibration object
 | 
			
		||||
  using shared_ptr = boost::shared_ptr<Cal3DS2>;
 | 
			
		||||
  using shared_ptr = std::shared_ptr<Cal3DS2>;
 | 
			
		||||
 | 
			
		||||
  /// @name Standard Constructors
 | 
			
		||||
  /// @{
 | 
			
		||||
| 
						 | 
				
			
			@ -94,8 +94,8 @@ class GTSAM_EXPORT Cal3DS2 : public Cal3DS2_Base {
 | 
			
		|||
  /// @{
 | 
			
		||||
 | 
			
		||||
  /// @return a deep copy of this object
 | 
			
		||||
  boost::shared_ptr<Base> clone() const override {
 | 
			
		||||
    return boost::shared_ptr<Base>(new Cal3DS2(*this));
 | 
			
		||||
  std::shared_ptr<Base> clone() const override {
 | 
			
		||||
    return std::shared_ptr<Base>(new Cal3DS2(*this));
 | 
			
		||||
  }
 | 
			
		||||
 | 
			
		||||
  /// @}
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -21,7 +21,7 @@
 | 
			
		|||
 | 
			
		||||
#include <gtsam/geometry/Cal3.h>
 | 
			
		||||
#include <gtsam/geometry/Point2.h>
 | 
			
		||||
#include <boost/shared_ptr.hpp>
 | 
			
		||||
#include <memory>
 | 
			
		||||
 | 
			
		||||
namespace gtsam {
 | 
			
		||||
 | 
			
		||||
| 
						 | 
				
			
			@ -49,7 +49,7 @@ class GTSAM_EXPORT Cal3DS2_Base : public Cal3 {
 | 
			
		|||
  enum { dimension = 9 };
 | 
			
		||||
 | 
			
		||||
  ///< shared pointer to stereo calibration object
 | 
			
		||||
  using shared_ptr = boost::shared_ptr<Cal3DS2_Base>;
 | 
			
		||||
  using shared_ptr = std::shared_ptr<Cal3DS2_Base>;
 | 
			
		||||
 | 
			
		||||
  /// @name Standard Constructors
 | 
			
		||||
  /// @{
 | 
			
		||||
| 
						 | 
				
			
			@ -146,8 +146,8 @@ class GTSAM_EXPORT Cal3DS2_Base : public Cal3 {
 | 
			
		|||
  /// @{
 | 
			
		||||
 | 
			
		||||
  /// @return a deep copy of this object
 | 
			
		||||
  virtual boost::shared_ptr<Cal3DS2_Base> clone() const {
 | 
			
		||||
    return boost::shared_ptr<Cal3DS2_Base>(new Cal3DS2_Base(*this));
 | 
			
		||||
  virtual std::shared_ptr<Cal3DS2_Base> clone() const {
 | 
			
		||||
    return std::shared_ptr<Cal3DS2_Base>(new Cal3DS2_Base(*this));
 | 
			
		||||
  }
 | 
			
		||||
 | 
			
		||||
  /// @}
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -22,7 +22,7 @@
 | 
			
		|||
#include <gtsam/geometry/Cal3.h>
 | 
			
		||||
#include <gtsam/geometry/Point2.h>
 | 
			
		||||
 | 
			
		||||
#include <boost/shared_ptr.hpp>
 | 
			
		||||
#include <memory>
 | 
			
		||||
 | 
			
		||||
#include <string>
 | 
			
		||||
 | 
			
		||||
| 
						 | 
				
			
			@ -57,7 +57,7 @@ class GTSAM_EXPORT Cal3Fisheye : public Cal3 {
 | 
			
		|||
 public:
 | 
			
		||||
  enum { dimension = 9 };
 | 
			
		||||
  ///< shared pointer to fisheye calibration object
 | 
			
		||||
  using shared_ptr = boost::shared_ptr<Cal3Fisheye>;
 | 
			
		||||
  using shared_ptr = std::shared_ptr<Cal3Fisheye>;
 | 
			
		||||
 | 
			
		||||
  /// @name Standard Constructors
 | 
			
		||||
  /// @{
 | 
			
		||||
| 
						 | 
				
			
			@ -174,8 +174,8 @@ class GTSAM_EXPORT Cal3Fisheye : public Cal3 {
 | 
			
		|||
  /// @{
 | 
			
		||||
 | 
			
		||||
  /// @return a deep copy of this object
 | 
			
		||||
  virtual boost::shared_ptr<Cal3Fisheye> clone() const {
 | 
			
		||||
    return boost::shared_ptr<Cal3Fisheye>(new Cal3Fisheye(*this));
 | 
			
		||||
  virtual std::shared_ptr<Cal3Fisheye> clone() const {
 | 
			
		||||
    return std::shared_ptr<Cal3Fisheye>(new Cal3Fisheye(*this));
 | 
			
		||||
  }
 | 
			
		||||
 | 
			
		||||
  /// @}
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -53,7 +53,7 @@ class GTSAM_EXPORT Cal3Unified : public Cal3DS2_Base {
 | 
			
		|||
  enum { dimension = 10 };
 | 
			
		||||
 | 
			
		||||
  ///< shared pointer to stereo calibration object
 | 
			
		||||
  using shared_ptr = boost::shared_ptr<Cal3Unified>;
 | 
			
		||||
  using shared_ptr = std::shared_ptr<Cal3Unified>;
 | 
			
		||||
 | 
			
		||||
  /// @name Standard Constructors
 | 
			
		||||
  /// @{
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -36,7 +36,7 @@ class GTSAM_EXPORT Cal3_S2 : public Cal3 {
 | 
			
		|||
  enum { dimension = 5 };
 | 
			
		||||
 | 
			
		||||
  ///< shared pointer to calibration object
 | 
			
		||||
  using shared_ptr = boost::shared_ptr<Cal3_S2>;
 | 
			
		||||
  using shared_ptr = std::shared_ptr<Cal3_S2>;
 | 
			
		||||
 | 
			
		||||
  /// @name Standard Constructors
 | 
			
		||||
  /// @{
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -35,7 +35,7 @@ class GTSAM_EXPORT Cal3_S2Stereo : public Cal3_S2 {
 | 
			
		|||
  enum { dimension = 6 };
 | 
			
		||||
 | 
			
		||||
  ///< shared pointer to stereo calibration object
 | 
			
		||||
  using shared_ptr = boost::shared_ptr<Cal3_S2Stereo>;
 | 
			
		||||
  using shared_ptr = std::shared_ptr<Cal3_S2Stereo>;
 | 
			
		||||
 | 
			
		||||
  /// @name Standard Constructors
 | 
			
		||||
  /// @{
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -21,7 +21,6 @@
 | 
			
		|||
 | 
			
		||||
#include <gtsam/geometry/CalibratedCamera.h>
 | 
			
		||||
#include <gtsam/geometry/Point2.h>
 | 
			
		||||
#include <boost/make_shared.hpp>
 | 
			
		||||
 | 
			
		||||
namespace gtsam {
 | 
			
		||||
 | 
			
		||||
| 
						 | 
				
			
			@ -245,7 +244,7 @@ class PinholePose: public PinholeBaseK<CALIBRATION> {
 | 
			
		|||
private:
 | 
			
		||||
 | 
			
		||||
  typedef PinholeBaseK<CALIBRATION> Base; ///< base class has 3D pose as private member
 | 
			
		||||
  boost::shared_ptr<CALIBRATION> K_; ///< shared pointer to fixed calibration
 | 
			
		||||
  std::shared_ptr<CALIBRATION> K_; ///< shared pointer to fixed calibration
 | 
			
		||||
 | 
			
		||||
public:
 | 
			
		||||
 | 
			
		||||
| 
						 | 
				
			
			@ -266,7 +265,7 @@ public:
 | 
			
		|||
  }
 | 
			
		||||
 | 
			
		||||
  /** constructor with pose and calibration */
 | 
			
		||||
  PinholePose(const Pose3& pose, const boost::shared_ptr<CALIBRATION>& K) :
 | 
			
		||||
  PinholePose(const Pose3& pose, const std::shared_ptr<CALIBRATION>& K) :
 | 
			
		||||
      Base(pose), K_(K) {
 | 
			
		||||
  }
 | 
			
		||||
 | 
			
		||||
| 
						 | 
				
			
			@ -281,14 +280,14 @@ public:
 | 
			
		|||
   * (theta 0 = looking in direction of positive X axis)
 | 
			
		||||
   * @param height camera height
 | 
			
		||||
   */
 | 
			
		||||
  static PinholePose Level(const boost::shared_ptr<CALIBRATION>& K,
 | 
			
		||||
  static PinholePose Level(const std::shared_ptr<CALIBRATION>& K,
 | 
			
		||||
      const Pose2& pose2, double height) {
 | 
			
		||||
    return PinholePose(Base::LevelPose(pose2, height), K);
 | 
			
		||||
  }
 | 
			
		||||
 | 
			
		||||
  /// PinholePose::level with default calibration
 | 
			
		||||
  static PinholePose Level(const Pose2& pose2, double height) {
 | 
			
		||||
    return PinholePose::Level(boost::make_shared<CALIBRATION>(), pose2, height);
 | 
			
		||||
    return PinholePose::Level(std::make_shared<CALIBRATION>(), pose2, height);
 | 
			
		||||
  }
 | 
			
		||||
 | 
			
		||||
  /**
 | 
			
		||||
| 
						 | 
				
			
			@ -301,8 +300,8 @@ public:
 | 
			
		|||
   * @param K optional calibration parameter
 | 
			
		||||
   */
 | 
			
		||||
  static PinholePose Lookat(const Point3& eye, const Point3& target,
 | 
			
		||||
      const Point3& upVector, const boost::shared_ptr<CALIBRATION>& K =
 | 
			
		||||
          boost::make_shared<CALIBRATION>()) {
 | 
			
		||||
      const Point3& upVector, const std::shared_ptr<CALIBRATION>& K =
 | 
			
		||||
          std::make_shared<CALIBRATION>()) {
 | 
			
		||||
    return PinholePose(Base::LookatPose(eye, target, upVector), K);
 | 
			
		||||
  }
 | 
			
		||||
 | 
			
		||||
| 
						 | 
				
			
			@ -362,7 +361,7 @@ public:
 | 
			
		|||
  }
 | 
			
		||||
 | 
			
		||||
  /// return shared pointer to calibration
 | 
			
		||||
  const boost::shared_ptr<CALIBRATION>& sharedCalibration() const {
 | 
			
		||||
  const std::shared_ptr<CALIBRATION>& sharedCalibration() const {
 | 
			
		||||
    return K_;
 | 
			
		||||
  }
 | 
			
		||||
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -42,7 +42,7 @@ class GTSAM_EXPORT EmptyCal {
 | 
			
		|||
  enum { dimension = 0 };
 | 
			
		||||
  EmptyCal() {}
 | 
			
		||||
  virtual ~EmptyCal() = default;
 | 
			
		||||
  using shared_ptr = boost::shared_ptr<EmptyCal>;
 | 
			
		||||
  using shared_ptr = std::shared_ptr<EmptyCal>;
 | 
			
		||||
 | 
			
		||||
  /// return DOF, dimensionality of tangent space
 | 
			
		||||
  inline static size_t Dim() { return dimension; }
 | 
			
		||||
| 
						 | 
				
			
			@ -87,11 +87,11 @@ class GTSAM_EXPORT SphericalCamera {
 | 
			
		|||
 | 
			
		||||
  /// Default constructor
 | 
			
		||||
  SphericalCamera()
 | 
			
		||||
      : pose_(Pose3()), emptyCal_(boost::make_shared<EmptyCal>()) {}
 | 
			
		||||
      : pose_(Pose3()), emptyCal_(std::make_shared<EmptyCal>()) {}
 | 
			
		||||
 | 
			
		||||
  /// Constructor with pose
 | 
			
		||||
  explicit SphericalCamera(const Pose3& pose)
 | 
			
		||||
      : pose_(pose), emptyCal_(boost::make_shared<EmptyCal>()) {}
 | 
			
		||||
      : pose_(pose), emptyCal_(std::make_shared<EmptyCal>()) {}
 | 
			
		||||
 | 
			
		||||
  /// Constructor with empty intrinsics (needed for smart factors)
 | 
			
		||||
  explicit SphericalCamera(const Pose3& pose,
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -33,7 +33,7 @@ using namespace gtsam;
 | 
			
		|||
 | 
			
		||||
typedef PinholePose<Cal3_S2> Camera;
 | 
			
		||||
 | 
			
		||||
static const Cal3_S2::shared_ptr K = boost::make_shared<Cal3_S2>(625, 625, 0, 0, 0);
 | 
			
		||||
static const Cal3_S2::shared_ptr K = std::make_shared<Cal3_S2>(625, 625, 0, 0, 0);
 | 
			
		||||
 | 
			
		||||
static const Pose3 pose(Rot3(Vector3(1, -1, -1).asDiagonal()), Point3(0, 0, 0.5));
 | 
			
		||||
static const Camera camera(pose, K);
 | 
			
		||||
| 
						 | 
				
			
			@ -263,8 +263,8 @@ TEST( PinholePose, range1) {
 | 
			
		|||
 | 
			
		||||
/* ************************************************************************* */
 | 
			
		||||
typedef PinholePose<Cal3Bundler> Camera2;
 | 
			
		||||
static const boost::shared_ptr<Cal3Bundler> K2 =
 | 
			
		||||
    boost::make_shared<Cal3Bundler>(625, 1e-3, 1e-3);
 | 
			
		||||
static const std::shared_ptr<Cal3Bundler> K2 =
 | 
			
		||||
    std::make_shared<Cal3Bundler>(625, 1e-3, 1e-3);
 | 
			
		||||
static const Camera2 camera2(pose1, K2);
 | 
			
		||||
static double range2(const Camera& camera, const Camera2& camera2) {
 | 
			
		||||
  return camera.range<Cal3Bundler>(camera2);
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -89,7 +89,7 @@ static Point3 landmark(0, 0, 5);
 | 
			
		|||
 | 
			
		||||
/* ************************************************************************* */
 | 
			
		||||
static StereoPoint2 project3(const Pose3& pose, const Point3& point, const Cal3_S2Stereo& K) {
 | 
			
		||||
  return StereoCamera(pose, boost::make_shared<Cal3_S2Stereo>(K)).project(point);
 | 
			
		||||
  return StereoCamera(pose, std::make_shared<Cal3_S2Stereo>(K)).project(point);
 | 
			
		||||
}
 | 
			
		||||
 | 
			
		||||
/* ************************************************************************* */
 | 
			
		||||
| 
						 | 
				
			
			@ -150,7 +150,7 @@ TEST( StereoCamera, backproject_case2)
 | 
			
		|||
}
 | 
			
		||||
 | 
			
		||||
static Point3 backproject3(const Pose3& pose, const StereoPoint2& point, const Cal3_S2Stereo& K) {
 | 
			
		||||
  return StereoCamera(pose, boost::make_shared<Cal3_S2Stereo>(K)).backproject(point);
 | 
			
		||||
  return StereoCamera(pose, std::make_shared<Cal3_S2Stereo>(K)).backproject(point);
 | 
			
		||||
}
 | 
			
		||||
 | 
			
		||||
/* ************************************************************************* */
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -35,8 +35,8 @@ using namespace gtsam;
 | 
			
		|||
 | 
			
		||||
// Some common constants
 | 
			
		||||
 | 
			
		||||
static const boost::shared_ptr<Cal3_S2> kSharedCal =  //
 | 
			
		||||
    boost::make_shared<Cal3_S2>(1500, 1200, 0.1, 640, 480);
 | 
			
		||||
static const std::shared_ptr<Cal3_S2> kSharedCal =  //
 | 
			
		||||
    std::make_shared<Cal3_S2>(1500, 1200, 0.1, 640, 480);
 | 
			
		||||
 | 
			
		||||
// Looking along X-axis, 1 meter above ground plane (x-y)
 | 
			
		||||
static const Rot3 upright = Rot3::Ypr(-M_PI / 2, 0., -M_PI / 2);
 | 
			
		||||
| 
						 | 
				
			
			@ -159,8 +159,8 @@ TEST(triangulation, twoCamerasLOSTvsDLT) {
 | 
			
		|||
//******************************************************************************
 | 
			
		||||
// Simple test with a well-behaved two camera situation with Cal3DS2 calibration.
 | 
			
		||||
TEST(triangulation, twoPosesCal3DS2) {
 | 
			
		||||
  static const boost::shared_ptr<Cal3DS2> sharedDistortedCal =  //
 | 
			
		||||
      boost::make_shared<Cal3DS2>(1500, 1200, 0, 640, 480, -.3, 0.1, 0.0001,
 | 
			
		||||
  static const std::shared_ptr<Cal3DS2> sharedDistortedCal =  //
 | 
			
		||||
      std::make_shared<Cal3DS2>(1500, 1200, 0, 640, 480, -.3, 0.1, 0.0001,
 | 
			
		||||
                                  -0.0003);
 | 
			
		||||
 | 
			
		||||
  PinholeCamera<Cal3DS2> camera1Distorted(kPose1, *sharedDistortedCal);
 | 
			
		||||
| 
						 | 
				
			
			@ -212,8 +212,8 @@ TEST(triangulation, twoPosesCal3DS2) {
 | 
			
		|||
// calibration.
 | 
			
		||||
TEST(triangulation, twoPosesFisheye) {
 | 
			
		||||
  using Calibration = Cal3Fisheye;
 | 
			
		||||
  static const boost::shared_ptr<Calibration> sharedDistortedCal =  //
 | 
			
		||||
      boost::make_shared<Calibration>(1500, 1200, .1, 640, 480, -.3, 0.1,
 | 
			
		||||
  static const std::shared_ptr<Calibration> sharedDistortedCal =  //
 | 
			
		||||
      std::make_shared<Calibration>(1500, 1200, .1, 640, 480, -.3, 0.1,
 | 
			
		||||
                                      0.0001, -0.0003);
 | 
			
		||||
 | 
			
		||||
  PinholeCamera<Calibration> camera1Distorted(kPose1, *sharedDistortedCal);
 | 
			
		||||
| 
						 | 
				
			
			@ -263,8 +263,8 @@ TEST(triangulation, twoPosesFisheye) {
 | 
			
		|||
//******************************************************************************
 | 
			
		||||
// Similar, but now with Bundler calibration
 | 
			
		||||
TEST(triangulation, twoPosesBundler) {
 | 
			
		||||
  boost::shared_ptr<Cal3Bundler> bundlerCal =  //
 | 
			
		||||
      boost::make_shared<Cal3Bundler>(1500, 0.1, 0.2, 640, 480);
 | 
			
		||||
  std::shared_ptr<Cal3Bundler> bundlerCal =  //
 | 
			
		||||
      std::make_shared<Cal3Bundler>(1500, 0.1, 0.2, 640, 480);
 | 
			
		||||
  PinholeCamera<Cal3Bundler> camera1(kPose1, *bundlerCal);
 | 
			
		||||
  PinholeCamera<Cal3Bundler> camera2(kPose2, *bundlerCal);
 | 
			
		||||
 | 
			
		||||
| 
						 | 
				
			
			@ -597,7 +597,7 @@ TEST(triangulation, onePose) {
 | 
			
		|||
 | 
			
		||||
//******************************************************************************
 | 
			
		||||
TEST(triangulation, StereoTriangulateNonlinear) {
 | 
			
		||||
  auto stereoK = boost::make_shared<Cal3_S2Stereo>(1733.75, 1733.75, 0, 689.645,
 | 
			
		||||
  auto stereoK = std::make_shared<Cal3_S2Stereo>(1733.75, 1733.75, 0, 689.645,
 | 
			
		||||
                                                   508.835, 0.0699612);
 | 
			
		||||
 | 
			
		||||
  // two camera kPoses m1, m2
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -123,7 +123,7 @@ GTSAM_EXPORT Point3 triangulateLOST(const std::vector<Pose3>& poses,
 | 
			
		|||
 */
 | 
			
		||||
template<class CALIBRATION>
 | 
			
		||||
std::pair<NonlinearFactorGraph, Values> triangulationGraph(
 | 
			
		||||
    const std::vector<Pose3>& poses, boost::shared_ptr<CALIBRATION> sharedCal,
 | 
			
		||||
    const std::vector<Pose3>& poses, std::shared_ptr<CALIBRATION> sharedCal,
 | 
			
		||||
    const Point2Vector& measurements, Key landmarkKey,
 | 
			
		||||
    const Point3& initialEstimate,
 | 
			
		||||
    const SharedNoiseModel& model = noiseModel::Unit::Create(2)) {
 | 
			
		||||
| 
						 | 
				
			
			@ -188,7 +188,7 @@ GTSAM_EXPORT Point3 optimize(const NonlinearFactorGraph& graph,
 | 
			
		|||
 */
 | 
			
		||||
template<class CALIBRATION>
 | 
			
		||||
Point3 triangulateNonlinear(const std::vector<Pose3>& poses,
 | 
			
		||||
    boost::shared_ptr<CALIBRATION> sharedCal,
 | 
			
		||||
    std::shared_ptr<CALIBRATION> sharedCal,
 | 
			
		||||
    const Point2Vector& measurements, const Point3& initialEstimate,
 | 
			
		||||
    const SharedNoiseModel& model = nullptr) {
 | 
			
		||||
 | 
			
		||||
| 
						 | 
				
			
			@ -236,7 +236,7 @@ projectionMatricesFromCameras(const CameraSet<CAMERA> &cameras) {
 | 
			
		|||
// overload, assuming pinholePose
 | 
			
		||||
template<class CALIBRATION>
 | 
			
		||||
std::vector<Matrix34, Eigen::aligned_allocator<Matrix34>> projectionMatricesFromPoses(
 | 
			
		||||
        const std::vector<Pose3> &poses, boost::shared_ptr<CALIBRATION> sharedCal) {
 | 
			
		||||
        const std::vector<Pose3> &poses, std::shared_ptr<CALIBRATION> sharedCal) {
 | 
			
		||||
  std::vector<Matrix34, Eigen::aligned_allocator<Matrix34>> projection_matrices;
 | 
			
		||||
  for (size_t i = 0; i < poses.size(); i++) {
 | 
			
		||||
    PinholePose<CALIBRATION> camera(poses.at(i), sharedCal);
 | 
			
		||||
| 
						 | 
				
			
			@ -422,7 +422,7 @@ inline Point3Vector calibrateMeasurements(
 | 
			
		|||
 */
 | 
			
		||||
template <class CALIBRATION>
 | 
			
		||||
Point3 triangulatePoint3(const std::vector<Pose3>& poses,
 | 
			
		||||
                         boost::shared_ptr<CALIBRATION> sharedCal,
 | 
			
		||||
                         std::shared_ptr<CALIBRATION> sharedCal,
 | 
			
		||||
                         const Point2Vector& measurements,
 | 
			
		||||
                         double rank_tol = 1e-9, bool optimize = false,
 | 
			
		||||
                         const SharedNoiseModel& model = nullptr,
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -106,7 +106,7 @@ GaussianConditional::shared_ptr GaussianMixture::operator()(
 | 
			
		|||
    const DiscreteValues &discreteValues) const {
 | 
			
		||||
  auto &ptr = conditionals_(discreteValues);
 | 
			
		||||
  if (!ptr) return nullptr;
 | 
			
		||||
  auto conditional = boost::dynamic_pointer_cast<GaussianConditional>(ptr);
 | 
			
		||||
  auto conditional = std::dynamic_pointer_cast<GaussianConditional>(ptr);
 | 
			
		||||
  if (conditional)
 | 
			
		||||
    return conditional;
 | 
			
		||||
  else
 | 
			
		||||
| 
						 | 
				
			
			@ -185,7 +185,7 @@ bool GaussianMixture::allFrontalsGiven(const VectorValues &given) const {
 | 
			
		|||
}
 | 
			
		||||
 | 
			
		||||
/* ************************************************************************* */
 | 
			
		||||
boost::shared_ptr<GaussianMixtureFactor> GaussianMixture::likelihood(
 | 
			
		||||
std::shared_ptr<GaussianMixtureFactor> GaussianMixture::likelihood(
 | 
			
		||||
    const VectorValues &given) const {
 | 
			
		||||
  if (!allFrontalsGiven(given)) {
 | 
			
		||||
    throw std::runtime_error(
 | 
			
		||||
| 
						 | 
				
			
			@ -208,12 +208,12 @@ boost::shared_ptr<GaussianMixtureFactor> GaussianMixture::likelihood(
 | 
			
		|||
          gfg.push_back(likelihood_m);
 | 
			
		||||
          Vector c(1);
 | 
			
		||||
          c << std::sqrt(2.0 * Cgm_Kgcm);
 | 
			
		||||
          auto constantFactor = boost::make_shared<JacobianFactor>(c);
 | 
			
		||||
          auto constantFactor = std::make_shared<JacobianFactor>(c);
 | 
			
		||||
          gfg.push_back(constantFactor);
 | 
			
		||||
          return boost::make_shared<JacobianFactor>(gfg);
 | 
			
		||||
          return std::make_shared<JacobianFactor>(gfg);
 | 
			
		||||
        }
 | 
			
		||||
      });
 | 
			
		||||
  return boost::make_shared<GaussianMixtureFactor>(
 | 
			
		||||
  return std::make_shared<GaussianMixtureFactor>(
 | 
			
		||||
      continuousParentKeys, discreteParentKeys, likelihoods);
 | 
			
		||||
}
 | 
			
		||||
 | 
			
		||||
| 
						 | 
				
			
			@ -252,7 +252,7 @@ GaussianMixture::prunerFunc(const DecisionTreeFactor &decisionTree) {
 | 
			
		|||
    if (gaussianMixtureKeySet == decisionTreeKeySet) {
 | 
			
		||||
      if (decisionTree(values) == 0.0) {
 | 
			
		||||
        // empty aka null pointer
 | 
			
		||||
        boost::shared_ptr<GaussianConditional> null;
 | 
			
		||||
        std::shared_ptr<GaussianConditional> null;
 | 
			
		||||
        return null;
 | 
			
		||||
      } else {
 | 
			
		||||
        return conditional;
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -55,7 +55,7 @@ class GTSAM_EXPORT GaussianMixture
 | 
			
		|||
      public Conditional<HybridFactor, GaussianMixture> {
 | 
			
		||||
 public:
 | 
			
		||||
  using This = GaussianMixture;
 | 
			
		||||
  using shared_ptr = boost::shared_ptr<GaussianMixture>;
 | 
			
		||||
  using shared_ptr = std::shared_ptr<GaussianMixture>;
 | 
			
		||||
  using BaseFactor = HybridFactor;
 | 
			
		||||
  using BaseConditional = Conditional<HybridFactor, GaussianMixture>;
 | 
			
		||||
 | 
			
		||||
| 
						 | 
				
			
			@ -164,7 +164,7 @@ class GTSAM_EXPORT GaussianMixture
 | 
			
		|||
   * Create a likelihood factor for a Gaussian mixture, return a Mixture factor
 | 
			
		||||
   * on the parents.
 | 
			
		||||
   */
 | 
			
		||||
  boost::shared_ptr<GaussianMixtureFactor> likelihood(
 | 
			
		||||
  std::shared_ptr<GaussianMixtureFactor> likelihood(
 | 
			
		||||
      const VectorValues &given) const;
 | 
			
		||||
 | 
			
		||||
  /// Getter for the underlying Conditionals DecisionTree
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -48,9 +48,9 @@ class GTSAM_EXPORT GaussianMixtureFactor : public HybridFactor {
 | 
			
		|||
 public:
 | 
			
		||||
  using Base = HybridFactor;
 | 
			
		||||
  using This = GaussianMixtureFactor;
 | 
			
		||||
  using shared_ptr = boost::shared_ptr<This>;
 | 
			
		||||
  using shared_ptr = std::shared_ptr<This>;
 | 
			
		||||
 | 
			
		||||
  using sharedFactor = boost::shared_ptr<GaussianFactor>;
 | 
			
		||||
  using sharedFactor = std::shared_ptr<GaussianFactor>;
 | 
			
		||||
 | 
			
		||||
  /// typedef for Decision Tree of Gaussian factors and log-constant.
 | 
			
		||||
  using Factors = DecisionTree<Key, sharedFactor>;
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -52,7 +52,7 @@ DecisionTreeFactor::shared_ptr HybridBayesNet::discreteConditionals() const {
 | 
			
		|||
      dtFactor = dtFactor * f;
 | 
			
		||||
    }
 | 
			
		||||
  }
 | 
			
		||||
  return boost::make_shared<DecisionTreeFactor>(dtFactor);
 | 
			
		||||
  return std::make_shared<DecisionTreeFactor>(dtFactor);
 | 
			
		||||
}
 | 
			
		||||
 | 
			
		||||
/* ************************************************************************* */
 | 
			
		||||
| 
						 | 
				
			
			@ -155,16 +155,16 @@ void HybridBayesNet::updateDiscreteConditionals(
 | 
			
		|||
 | 
			
		||||
      // Apply prunerFunc to the underlying AlgebraicDecisionTree
 | 
			
		||||
      auto discreteTree =
 | 
			
		||||
          boost::dynamic_pointer_cast<DecisionTreeFactor::ADT>(discrete);
 | 
			
		||||
          std::dynamic_pointer_cast<DecisionTreeFactor::ADT>(discrete);
 | 
			
		||||
      DecisionTreeFactor::ADT prunedDiscreteTree =
 | 
			
		||||
          discreteTree->apply(prunerFunc(prunedDecisionTree, *conditional));
 | 
			
		||||
 | 
			
		||||
      // Create the new (hybrid) conditional
 | 
			
		||||
      KeyVector frontals(discrete->frontals().begin(),
 | 
			
		||||
                         discrete->frontals().end());
 | 
			
		||||
      auto prunedDiscrete = boost::make_shared<DiscreteLookupTable>(
 | 
			
		||||
      auto prunedDiscrete = std::make_shared<DiscreteLookupTable>(
 | 
			
		||||
          frontals.size(), conditional->discreteKeys(), prunedDiscreteTree);
 | 
			
		||||
      conditional = boost::make_shared<HybridConditional>(prunedDiscrete);
 | 
			
		||||
      conditional = std::make_shared<HybridConditional>(prunedDiscrete);
 | 
			
		||||
 | 
			
		||||
      // Add it back to the BayesNet
 | 
			
		||||
      this->at(i) = conditional;
 | 
			
		||||
| 
						 | 
				
			
			@ -194,7 +194,7 @@ HybridBayesNet HybridBayesNet::prune(size_t maxNrLeaves) {
 | 
			
		|||
  for (auto &&conditional : *this) {
 | 
			
		||||
    if (auto gm = conditional->asMixture()) {
 | 
			
		||||
      // Make a copy of the Gaussian mixture and prune it!
 | 
			
		||||
      auto prunedGaussianMixture = boost::make_shared<GaussianMixture>(*gm);
 | 
			
		||||
      auto prunedGaussianMixture = std::make_shared<GaussianMixture>(*gm);
 | 
			
		||||
      prunedGaussianMixture->prune(decisionTree);  // imperative :-(
 | 
			
		||||
 | 
			
		||||
      // Type-erase and add to the pruned Bayes Net fragment.
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -37,8 +37,8 @@ class GTSAM_EXPORT HybridBayesNet : public BayesNet<HybridConditional> {
 | 
			
		|||
  using Base = BayesNet<HybridConditional>;
 | 
			
		||||
  using This = HybridBayesNet;
 | 
			
		||||
  using ConditionalType = HybridConditional;
 | 
			
		||||
  using shared_ptr = boost::shared_ptr<HybridBayesNet>;
 | 
			
		||||
  using sharedConditional = boost::shared_ptr<ConditionalType>;
 | 
			
		||||
  using shared_ptr = std::shared_ptr<HybridBayesNet>;
 | 
			
		||||
  using sharedConditional = std::shared_ptr<ConditionalType>;
 | 
			
		||||
 | 
			
		||||
  /// @name Standard Constructors
 | 
			
		||||
  /// @{
 | 
			
		||||
| 
						 | 
				
			
			@ -66,7 +66,7 @@ class GTSAM_EXPORT HybridBayesNet : public BayesNet<HybridConditional> {
 | 
			
		|||
   *
 | 
			
		||||
   * This is the "native" push back, as this class stores hybrid conditionals.
 | 
			
		||||
   */
 | 
			
		||||
  void push_back(boost::shared_ptr<HybridConditional> conditional) {
 | 
			
		||||
  void push_back(std::shared_ptr<HybridConditional> conditional) {
 | 
			
		||||
    factors_.push_back(conditional);
 | 
			
		||||
  }
 | 
			
		||||
 | 
			
		||||
| 
						 | 
				
			
			@ -80,8 +80,8 @@ class GTSAM_EXPORT HybridBayesNet : public BayesNet<HybridConditional> {
 | 
			
		|||
   */
 | 
			
		||||
  template <class Conditional>
 | 
			
		||||
  void emplace_back(Conditional *conditional) {
 | 
			
		||||
    factors_.push_back(boost::make_shared<HybridConditional>(
 | 
			
		||||
        boost::shared_ptr<Conditional>(conditional)));
 | 
			
		||||
    factors_.push_back(std::make_shared<HybridConditional>(
 | 
			
		||||
        std::shared_ptr<Conditional>(conditional)));
 | 
			
		||||
  }
 | 
			
		||||
 | 
			
		||||
  /**
 | 
			
		||||
| 
						 | 
				
			
			@ -93,12 +93,12 @@ class GTSAM_EXPORT HybridBayesNet : public BayesNet<HybridConditional> {
 | 
			
		|||
   *
 | 
			
		||||
   * Example:
 | 
			
		||||
   *   auto shared_ptr_to_a_conditional =
 | 
			
		||||
   *     boost::make_shared<GaussianMixture>(...);
 | 
			
		||||
   *     std::make_shared<GaussianMixture>(...);
 | 
			
		||||
   *  hbn.push_back(shared_ptr_to_a_conditional);
 | 
			
		||||
   */
 | 
			
		||||
  void push_back(HybridConditional &&conditional) {
 | 
			
		||||
    factors_.push_back(
 | 
			
		||||
        boost::make_shared<HybridConditional>(std::move(conditional)));
 | 
			
		||||
        std::make_shared<HybridConditional>(std::move(conditional)));
 | 
			
		||||
  }
 | 
			
		||||
 | 
			
		||||
  /**
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -114,13 +114,13 @@ struct HybridAssignmentData {
 | 
			
		|||
      conditional = hybrid_conditional->asGaussian();
 | 
			
		||||
    } else {
 | 
			
		||||
      // Discrete only conditional, so we set to empty gaussian conditional
 | 
			
		||||
      conditional = boost::make_shared<GaussianConditional>();
 | 
			
		||||
      conditional = std::make_shared<GaussianConditional>();
 | 
			
		||||
    }
 | 
			
		||||
 | 
			
		||||
    GaussianBayesTree::sharedNode clique;
 | 
			
		||||
    if (conditional) {
 | 
			
		||||
      // Create the GaussianClique for the current node
 | 
			
		||||
      clique = boost::make_shared<GaussianBayesTree::Node>(conditional);
 | 
			
		||||
      clique = std::make_shared<GaussianBayesTree::Node>(conditional);
 | 
			
		||||
      // Add the current clique to the GaussianBayesTree.
 | 
			
		||||
      parentData.gaussianbayesTree_->addClique(clique,
 | 
			
		||||
                                               parentData.parentClique_);
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -48,10 +48,10 @@ class GTSAM_EXPORT HybridBayesTreeClique
 | 
			
		|||
  typedef HybridBayesTreeClique This;
 | 
			
		||||
  typedef BayesTreeCliqueBase<HybridBayesTreeClique, HybridGaussianFactorGraph>
 | 
			
		||||
      Base;
 | 
			
		||||
  typedef boost::shared_ptr<This> shared_ptr;
 | 
			
		||||
  typedef boost::weak_ptr<This> weak_ptr;
 | 
			
		||||
  typedef std::shared_ptr<This> shared_ptr;
 | 
			
		||||
  typedef std::weak_ptr<This> weak_ptr;
 | 
			
		||||
  HybridBayesTreeClique() {}
 | 
			
		||||
  HybridBayesTreeClique(const boost::shared_ptr<HybridConditional>& conditional)
 | 
			
		||||
  HybridBayesTreeClique(const std::shared_ptr<HybridConditional>& conditional)
 | 
			
		||||
      : Base(conditional) {}
 | 
			
		||||
  ///< Copy constructor
 | 
			
		||||
  HybridBayesTreeClique(const HybridBayesTreeClique& clique) : Base(clique) {}
 | 
			
		||||
| 
						 | 
				
			
			@ -67,7 +67,7 @@ class GTSAM_EXPORT HybridBayesTree : public BayesTree<HybridBayesTreeClique> {
 | 
			
		|||
 | 
			
		||||
 public:
 | 
			
		||||
  typedef HybridBayesTree This;
 | 
			
		||||
  typedef boost::shared_ptr<This> shared_ptr;
 | 
			
		||||
  typedef std::shared_ptr<This> shared_ptr;
 | 
			
		||||
 | 
			
		||||
  /// @name Standard interface
 | 
			
		||||
  /// @{
 | 
			
		||||
| 
						 | 
				
			
			@ -142,14 +142,14 @@ class BayesTreeOrphanWrapper<HybridBayesTreeClique> : public HybridConditional {
 | 
			
		|||
  typedef HybridBayesTreeClique CliqueType;
 | 
			
		||||
  typedef HybridConditional Base;
 | 
			
		||||
 | 
			
		||||
  boost::shared_ptr<CliqueType> clique;
 | 
			
		||||
  std::shared_ptr<CliqueType> clique;
 | 
			
		||||
 | 
			
		||||
  /**
 | 
			
		||||
   * @brief Construct a new Bayes Tree Orphan Wrapper object.
 | 
			
		||||
   *
 | 
			
		||||
   * @param clique Bayes tree clique.
 | 
			
		||||
   */
 | 
			
		||||
  BayesTreeOrphanWrapper(const boost::shared_ptr<CliqueType>& clique)
 | 
			
		||||
  BayesTreeOrphanWrapper(const std::shared_ptr<CliqueType>& clique)
 | 
			
		||||
      : clique(clique) {
 | 
			
		||||
    // Store parent keys in our base type factor so that eliminating those
 | 
			
		||||
    // parent keys will pull this subtree into the elimination.
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -39,7 +39,7 @@ HybridConditional::HybridConditional(const KeyVector &continuousFrontals,
 | 
			
		|||
 | 
			
		||||
/* ************************************************************************ */
 | 
			
		||||
HybridConditional::HybridConditional(
 | 
			
		||||
    const boost::shared_ptr<GaussianConditional> &continuousConditional)
 | 
			
		||||
    const std::shared_ptr<GaussianConditional> &continuousConditional)
 | 
			
		||||
    : HybridConditional(continuousConditional->keys(), {},
 | 
			
		||||
                        continuousConditional->nrFrontals()) {
 | 
			
		||||
  inner_ = continuousConditional;
 | 
			
		||||
| 
						 | 
				
			
			@ -47,7 +47,7 @@ HybridConditional::HybridConditional(
 | 
			
		|||
 | 
			
		||||
/* ************************************************************************ */
 | 
			
		||||
HybridConditional::HybridConditional(
 | 
			
		||||
    const boost::shared_ptr<DiscreteConditional> &discreteConditional)
 | 
			
		||||
    const std::shared_ptr<DiscreteConditional> &discreteConditional)
 | 
			
		||||
    : HybridConditional({}, discreteConditional->discreteKeys(),
 | 
			
		||||
                        discreteConditional->nrFrontals()) {
 | 
			
		||||
  inner_ = discreteConditional;
 | 
			
		||||
| 
						 | 
				
			
			@ -55,7 +55,7 @@ HybridConditional::HybridConditional(
 | 
			
		|||
 | 
			
		||||
/* ************************************************************************ */
 | 
			
		||||
HybridConditional::HybridConditional(
 | 
			
		||||
    const boost::shared_ptr<GaussianMixture> &gaussianMixture)
 | 
			
		||||
    const std::shared_ptr<GaussianMixture> &gaussianMixture)
 | 
			
		||||
    : BaseFactor(KeyVector(gaussianMixture->keys().begin(),
 | 
			
		||||
                           gaussianMixture->keys().begin() +
 | 
			
		||||
                               gaussianMixture->nrContinuous()),
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -25,8 +25,7 @@
 | 
			
		|||
#include <gtsam/inference/Key.h>
 | 
			
		||||
#include <gtsam/linear/GaussianConditional.h>
 | 
			
		||||
 | 
			
		||||
#include <boost/make_shared.hpp>
 | 
			
		||||
#include <boost/shared_ptr.hpp>
 | 
			
		||||
#include <memory>
 | 
			
		||||
#include <stdexcept>
 | 
			
		||||
#include <string>
 | 
			
		||||
#include <typeinfo>
 | 
			
		||||
| 
						 | 
				
			
			@ -63,14 +62,14 @@ class GTSAM_EXPORT HybridConditional
 | 
			
		|||
 public:
 | 
			
		||||
  // typedefs needed to play nice with gtsam
 | 
			
		||||
  typedef HybridConditional This;              ///< Typedef to this class
 | 
			
		||||
  typedef boost::shared_ptr<This> shared_ptr;  ///< shared_ptr to this class
 | 
			
		||||
  typedef std::shared_ptr<This> shared_ptr;  ///< shared_ptr to this class
 | 
			
		||||
  typedef HybridFactor BaseFactor;  ///< Typedef to our factor base class
 | 
			
		||||
  typedef Conditional<BaseFactor, This>
 | 
			
		||||
      BaseConditional;  ///< Typedef to our conditional base class
 | 
			
		||||
 | 
			
		||||
 protected:
 | 
			
		||||
  /// Type-erased pointer to the inner type
 | 
			
		||||
  boost::shared_ptr<Factor> inner_;
 | 
			
		||||
  std::shared_ptr<Factor> inner_;
 | 
			
		||||
 | 
			
		||||
 public:
 | 
			
		||||
  /// @name Standard Constructors
 | 
			
		||||
| 
						 | 
				
			
			@ -111,7 +110,7 @@ class GTSAM_EXPORT HybridConditional
 | 
			
		|||
   * HybridConditional.
 | 
			
		||||
   */
 | 
			
		||||
  HybridConditional(
 | 
			
		||||
      const boost::shared_ptr<GaussianConditional>& continuousConditional);
 | 
			
		||||
      const std::shared_ptr<GaussianConditional>& continuousConditional);
 | 
			
		||||
 | 
			
		||||
  /**
 | 
			
		||||
   * @brief Construct a new Hybrid Conditional object
 | 
			
		||||
| 
						 | 
				
			
			@ -120,7 +119,7 @@ class GTSAM_EXPORT HybridConditional
 | 
			
		|||
   * HybridConditional.
 | 
			
		||||
   */
 | 
			
		||||
  HybridConditional(
 | 
			
		||||
      const boost::shared_ptr<DiscreteConditional>& discreteConditional);
 | 
			
		||||
      const std::shared_ptr<DiscreteConditional>& discreteConditional);
 | 
			
		||||
 | 
			
		||||
  /**
 | 
			
		||||
   * @brief Construct a new Hybrid Conditional object
 | 
			
		||||
| 
						 | 
				
			
			@ -128,7 +127,7 @@ class GTSAM_EXPORT HybridConditional
 | 
			
		|||
   * @param gaussianMixture Gaussian Mixture Conditional used to create the
 | 
			
		||||
   * HybridConditional.
 | 
			
		||||
   */
 | 
			
		||||
  HybridConditional(const boost::shared_ptr<GaussianMixture>& gaussianMixture);
 | 
			
		||||
  HybridConditional(const std::shared_ptr<GaussianMixture>& gaussianMixture);
 | 
			
		||||
 | 
			
		||||
  /// @}
 | 
			
		||||
  /// @name Testable
 | 
			
		||||
| 
						 | 
				
			
			@ -152,7 +151,7 @@ class GTSAM_EXPORT HybridConditional
 | 
			
		|||
   * @return GaussianMixture::shared_ptr otherwise
 | 
			
		||||
   */
 | 
			
		||||
  GaussianMixture::shared_ptr asMixture() const {
 | 
			
		||||
    return boost::dynamic_pointer_cast<GaussianMixture>(inner_);
 | 
			
		||||
    return std::dynamic_pointer_cast<GaussianMixture>(inner_);
 | 
			
		||||
  }
 | 
			
		||||
 | 
			
		||||
  /**
 | 
			
		||||
| 
						 | 
				
			
			@ -161,7 +160,7 @@ class GTSAM_EXPORT HybridConditional
 | 
			
		|||
   * @return GaussianConditional::shared_ptr otherwise
 | 
			
		||||
   */
 | 
			
		||||
  GaussianConditional::shared_ptr asGaussian() const {
 | 
			
		||||
    return boost::dynamic_pointer_cast<GaussianConditional>(inner_);
 | 
			
		||||
    return std::dynamic_pointer_cast<GaussianConditional>(inner_);
 | 
			
		||||
  }
 | 
			
		||||
 | 
			
		||||
  /**
 | 
			
		||||
| 
						 | 
				
			
			@ -170,11 +169,11 @@ class GTSAM_EXPORT HybridConditional
 | 
			
		|||
   * @return DiscreteConditional::shared_ptr
 | 
			
		||||
   */
 | 
			
		||||
  DiscreteConditional::shared_ptr asDiscrete() const {
 | 
			
		||||
    return boost::dynamic_pointer_cast<DiscreteConditional>(inner_);
 | 
			
		||||
    return std::dynamic_pointer_cast<DiscreteConditional>(inner_);
 | 
			
		||||
  }
 | 
			
		||||
 | 
			
		||||
  /// Get the type-erased pointer to the inner type
 | 
			
		||||
  boost::shared_ptr<Factor> inner() const { return inner_; }
 | 
			
		||||
  std::shared_ptr<Factor> inner() const { return inner_; }
 | 
			
		||||
 | 
			
		||||
  /// Return the error of the underlying conditional.
 | 
			
		||||
  double error(const HybridValues& values) const override;
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -37,7 +37,7 @@ class GTSAM_EXPORT HybridEliminationTree
 | 
			
		|||
  typedef EliminationTree<HybridBayesNet, HybridGaussianFactorGraph>
 | 
			
		||||
      Base;                                    ///< Base class
 | 
			
		||||
  typedef HybridEliminationTree This;          ///< This class
 | 
			
		||||
  typedef boost::shared_ptr<This> shared_ptr;  ///< Shared pointer to this class
 | 
			
		||||
  typedef std::shared_ptr<This> shared_ptr;  ///< Shared pointer to this class
 | 
			
		||||
 | 
			
		||||
  /// @name Constructors
 | 
			
		||||
  /// @{
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -64,7 +64,7 @@ class GTSAM_EXPORT HybridFactor : public Factor {
 | 
			
		|||
 public:
 | 
			
		||||
  // typedefs needed to play nice with gtsam
 | 
			
		||||
  typedef HybridFactor This;  ///< This class
 | 
			
		||||
  typedef boost::shared_ptr<HybridFactor>
 | 
			
		||||
  typedef std::shared_ptr<HybridFactor>
 | 
			
		||||
      shared_ptr;       ///< shared_ptr to this class
 | 
			
		||||
  typedef Factor Base;  ///< Our base class
 | 
			
		||||
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -28,12 +28,12 @@ namespace gtsam {
 | 
			
		|||
std::set<DiscreteKey> HybridFactorGraph::discreteKeys() const {
 | 
			
		||||
  std::set<DiscreteKey> keys;
 | 
			
		||||
  for (auto& factor : factors_) {
 | 
			
		||||
    if (auto p = boost::dynamic_pointer_cast<DecisionTreeFactor>(factor)) {
 | 
			
		||||
    if (auto p = std::dynamic_pointer_cast<DecisionTreeFactor>(factor)) {
 | 
			
		||||
      for (const DiscreteKey& key : p->discreteKeys()) {
 | 
			
		||||
        keys.insert(key);
 | 
			
		||||
      }
 | 
			
		||||
    }
 | 
			
		||||
    if (auto p = boost::dynamic_pointer_cast<HybridFactor>(factor)) {
 | 
			
		||||
    if (auto p = std::dynamic_pointer_cast<HybridFactor>(factor)) {
 | 
			
		||||
      for (const DiscreteKey& key : p->discreteKeys()) {
 | 
			
		||||
        keys.insert(key);
 | 
			
		||||
      }
 | 
			
		||||
| 
						 | 
				
			
			@ -65,7 +65,7 @@ std::unordered_map<Key, DiscreteKey> HybridFactorGraph::discreteKeyMap() const {
 | 
			
		|||
const KeySet HybridFactorGraph::continuousKeySet() const {
 | 
			
		||||
  KeySet keys;
 | 
			
		||||
  for (auto& factor : factors_) {
 | 
			
		||||
    if (auto p = boost::dynamic_pointer_cast<HybridFactor>(factor)) {
 | 
			
		||||
    if (auto p = std::dynamic_pointer_cast<HybridFactor>(factor)) {
 | 
			
		||||
      for (const Key& key : p->continuousKeys()) {
 | 
			
		||||
        keys.insert(key);
 | 
			
		||||
      }
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -30,7 +30,7 @@ namespace gtsam {
 | 
			
		|||
class DiscreteFactor;
 | 
			
		||||
class Ordering;
 | 
			
		||||
 | 
			
		||||
using SharedFactor = boost::shared_ptr<Factor>;
 | 
			
		||||
using SharedFactor = std::shared_ptr<Factor>;
 | 
			
		||||
 | 
			
		||||
/**
 | 
			
		||||
 * Hybrid Factor Graph
 | 
			
		||||
| 
						 | 
				
			
			@ -40,7 +40,7 @@ class HybridFactorGraph : public FactorGraph<Factor> {
 | 
			
		|||
 public:
 | 
			
		||||
  using Base = FactorGraph<Factor>;
 | 
			
		||||
  using This = HybridFactorGraph;              ///< this class
 | 
			
		||||
  using shared_ptr = boost::shared_ptr<This>;  ///< shared_ptr to This
 | 
			
		||||
  using shared_ptr = std::shared_ptr<This>;  ///< shared_ptr to This
 | 
			
		||||
 | 
			
		||||
  using Values = gtsam::Values;  ///< backwards compatibility
 | 
			
		||||
  using Indices = KeyVector;     ///> map from keys to values
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -57,12 +57,12 @@ template class EliminateableFactorGraph<HybridGaussianFactorGraph>;
 | 
			
		|||
 | 
			
		||||
using OrphanWrapper = BayesTreeOrphanWrapper<HybridBayesTree::Clique>;
 | 
			
		||||
 | 
			
		||||
using boost::dynamic_pointer_cast;
 | 
			
		||||
using std::dynamic_pointer_cast;
 | 
			
		||||
 | 
			
		||||
/* ************************************************************************ */
 | 
			
		||||
// Throw a runtime exception for method specified in string s, and factor f:
 | 
			
		||||
static void throwRuntimeError(const std::string &s,
 | 
			
		||||
                              const boost::shared_ptr<Factor> &f) {
 | 
			
		||||
                              const std::shared_ptr<Factor> &f) {
 | 
			
		||||
  auto &fr = *f;
 | 
			
		||||
  throw std::runtime_error(s + " not implemented for factor type " +
 | 
			
		||||
                           demangle(typeid(fr).name()) + ".");
 | 
			
		||||
| 
						 | 
				
			
			@ -135,7 +135,7 @@ GaussianFactorGraphTree HybridGaussianFactorGraph::assembleGraphTree() const {
 | 
			
		|||
}
 | 
			
		||||
 | 
			
		||||
/* ************************************************************************ */
 | 
			
		||||
static std::pair<HybridConditional::shared_ptr, boost::shared_ptr<Factor>>
 | 
			
		||||
static std::pair<HybridConditional::shared_ptr, std::shared_ptr<Factor>>
 | 
			
		||||
continuousElimination(const HybridGaussianFactorGraph &factors,
 | 
			
		||||
                      const Ordering &frontalKeys) {
 | 
			
		||||
  GaussianFactorGraph gfg;
 | 
			
		||||
| 
						 | 
				
			
			@ -155,11 +155,11 @@ continuousElimination(const HybridGaussianFactorGraph &factors,
 | 
			
		|||
  }
 | 
			
		||||
 | 
			
		||||
  auto result = EliminatePreferCholesky(gfg, frontalKeys);
 | 
			
		||||
  return {boost::make_shared<HybridConditional>(result.first), result.second};
 | 
			
		||||
  return {std::make_shared<HybridConditional>(result.first), result.second};
 | 
			
		||||
}
 | 
			
		||||
 | 
			
		||||
/* ************************************************************************ */
 | 
			
		||||
static std::pair<HybridConditional::shared_ptr, boost::shared_ptr<Factor>>
 | 
			
		||||
static std::pair<HybridConditional::shared_ptr, std::shared_ptr<Factor>>
 | 
			
		||||
discreteElimination(const HybridGaussianFactorGraph &factors,
 | 
			
		||||
                    const Ordering &frontalKeys) {
 | 
			
		||||
  DiscreteFactorGraph dfg;
 | 
			
		||||
| 
						 | 
				
			
			@ -182,7 +182,7 @@ discreteElimination(const HybridGaussianFactorGraph &factors,
 | 
			
		|||
  // NOTE: This does sum-product. For max-product, use EliminateForMPE.
 | 
			
		||||
  auto result = EliminateDiscrete(dfg, frontalKeys);
 | 
			
		||||
 | 
			
		||||
  return {boost::make_shared<HybridConditional>(result.first), result.second};
 | 
			
		||||
  return {std::make_shared<HybridConditional>(result.first), result.second};
 | 
			
		||||
}
 | 
			
		||||
 | 
			
		||||
/* ************************************************************************ */
 | 
			
		||||
| 
						 | 
				
			
			@ -201,7 +201,7 @@ GaussianFactorGraphTree removeEmpty(const GaussianFactorGraphTree &sum) {
 | 
			
		|||
}
 | 
			
		||||
 | 
			
		||||
/* ************************************************************************ */
 | 
			
		||||
static std::pair<HybridConditional::shared_ptr, boost::shared_ptr<Factor>>
 | 
			
		||||
static std::pair<HybridConditional::shared_ptr, std::shared_ptr<Factor>>
 | 
			
		||||
hybridElimination(const HybridGaussianFactorGraph &factors,
 | 
			
		||||
                  const Ordering &frontalKeys,
 | 
			
		||||
                  const KeyVector &continuousSeparator,
 | 
			
		||||
| 
						 | 
				
			
			@ -220,7 +220,7 @@ hybridElimination(const HybridGaussianFactorGraph &factors,
 | 
			
		|||
  // FG has a nullptr as we're looping over the factors.
 | 
			
		||||
  factorGraphTree = removeEmpty(factorGraphTree);
 | 
			
		||||
 | 
			
		||||
  using Result = std::pair<boost::shared_ptr<GaussianConditional>,
 | 
			
		||||
  using Result = std::pair<std::shared_ptr<GaussianConditional>,
 | 
			
		||||
                           GaussianMixtureFactor::sharedFactor>;
 | 
			
		||||
 | 
			
		||||
  // This is the elimination method on the leaf nodes
 | 
			
		||||
| 
						 | 
				
			
			@ -256,7 +256,7 @@ hybridElimination(const HybridGaussianFactorGraph &factors,
 | 
			
		|||
  std::tie(conditionals, newFactors) = unzip(eliminationResults);
 | 
			
		||||
 | 
			
		||||
  // Create the GaussianMixture from the conditionals
 | 
			
		||||
  auto gaussianMixture = boost::make_shared<GaussianMixture>(
 | 
			
		||||
  auto gaussianMixture = std::make_shared<GaussianMixture>(
 | 
			
		||||
      frontalKeys, continuousSeparator, discreteSeparator, conditionals);
 | 
			
		||||
 | 
			
		||||
  if (continuousSeparator.empty()) {
 | 
			
		||||
| 
						 | 
				
			
			@ -275,8 +275,8 @@ hybridElimination(const HybridGaussianFactorGraph &factors,
 | 
			
		|||
    };
 | 
			
		||||
 | 
			
		||||
    DecisionTree<Key, double> probabilities(eliminationResults, probability);
 | 
			
		||||
    return {boost::make_shared<HybridConditional>(gaussianMixture),
 | 
			
		||||
            boost::make_shared<DecisionTreeFactor>(discreteSeparator,
 | 
			
		||||
    return {std::make_shared<HybridConditional>(gaussianMixture),
 | 
			
		||||
            std::make_shared<DecisionTreeFactor>(discreteSeparator,
 | 
			
		||||
                                                   probabilities)};
 | 
			
		||||
  } else {
 | 
			
		||||
    // Otherwise, we create a resulting GaussianMixtureFactor on the separator,
 | 
			
		||||
| 
						 | 
				
			
			@ -286,7 +286,7 @@ hybridElimination(const HybridGaussianFactorGraph &factors,
 | 
			
		|||
    auto correct = [&](const Result &pair) -> GaussianFactor::shared_ptr {
 | 
			
		||||
      const auto &factor = pair.second;
 | 
			
		||||
      if (!factor) return factor;  // TODO(dellaert): not loving this.
 | 
			
		||||
      auto hf = boost::dynamic_pointer_cast<HessianFactor>(factor);
 | 
			
		||||
      auto hf = std::dynamic_pointer_cast<HessianFactor>(factor);
 | 
			
		||||
      if (!hf) throw std::runtime_error("Expected HessianFactor!");
 | 
			
		||||
      hf->constantTerm() += 2.0 * pair.first->logNormalizationConstant();
 | 
			
		||||
      return hf;
 | 
			
		||||
| 
						 | 
				
			
			@ -294,10 +294,10 @@ hybridElimination(const HybridGaussianFactorGraph &factors,
 | 
			
		|||
 | 
			
		||||
    GaussianMixtureFactor::Factors correctedFactors(eliminationResults,
 | 
			
		||||
                                                    correct);
 | 
			
		||||
    const auto mixtureFactor = boost::make_shared<GaussianMixtureFactor>(
 | 
			
		||||
    const auto mixtureFactor = std::make_shared<GaussianMixtureFactor>(
 | 
			
		||||
        continuousSeparator, discreteSeparator, newFactors);
 | 
			
		||||
 | 
			
		||||
    return {boost::make_shared<HybridConditional>(gaussianMixture),
 | 
			
		||||
    return {std::make_shared<HybridConditional>(gaussianMixture),
 | 
			
		||||
            mixtureFactor};
 | 
			
		||||
  }
 | 
			
		||||
}
 | 
			
		||||
| 
						 | 
				
			
			@ -316,7 +316,7 @@ hybridElimination(const HybridGaussianFactorGraph &factors,
 | 
			
		|||
 * eliminate a discrete variable (as specified in the ordering), the result will
 | 
			
		||||
 * be INCORRECT and there will be NO error raised.
 | 
			
		||||
 */
 | 
			
		||||
std::pair<HybridConditional::shared_ptr, boost::shared_ptr<Factor>>  //
 | 
			
		||||
std::pair<HybridConditional::shared_ptr, std::shared_ptr<Factor>>  //
 | 
			
		||||
EliminateHybrid(const HybridGaussianFactorGraph &factors,
 | 
			
		||||
                const Ordering &frontalKeys) {
 | 
			
		||||
  // NOTE: Because we are in the Conditional Gaussian regime there are only
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -52,7 +52,7 @@ class HybridValues;
 | 
			
		|||
 * @ingroup hybrid
 | 
			
		||||
 */
 | 
			
		||||
GTSAM_EXPORT
 | 
			
		||||
std::pair<boost::shared_ptr<HybridConditional>, boost::shared_ptr<Factor>>
 | 
			
		||||
std::pair<std::shared_ptr<HybridConditional>, std::shared_ptr<Factor>>
 | 
			
		||||
EliminateHybrid(const HybridGaussianFactorGraph& factors, const Ordering& keys);
 | 
			
		||||
 | 
			
		||||
/**
 | 
			
		||||
| 
						 | 
				
			
			@ -80,8 +80,8 @@ struct EliminationTraits<HybridGaussianFactorGraph> {
 | 
			
		|||
  typedef HybridBayesTree BayesTreeType;        ///< Type of Bayes tree
 | 
			
		||||
  typedef HybridJunctionTree JunctionTreeType;  ///< Type of Junction tree
 | 
			
		||||
  /// The default dense elimination function
 | 
			
		||||
  static std::pair<boost::shared_ptr<ConditionalType>,
 | 
			
		||||
                   boost::shared_ptr<FactorType>>
 | 
			
		||||
  static std::pair<std::shared_ptr<ConditionalType>,
 | 
			
		||||
                   std::shared_ptr<FactorType>>
 | 
			
		||||
  DefaultEliminate(const FactorGraphType& factors, const Ordering& keys) {
 | 
			
		||||
    return EliminateHybrid(factors, keys);
 | 
			
		||||
  }
 | 
			
		||||
| 
						 | 
				
			
			@ -114,7 +114,7 @@ class GTSAM_EXPORT HybridGaussianFactorGraph
 | 
			
		|||
  using This = HybridGaussianFactorGraph;  ///< this class
 | 
			
		||||
  using BaseEliminateable =
 | 
			
		||||
      EliminateableFactorGraph<This>;          ///< for elimination
 | 
			
		||||
  using shared_ptr = boost::shared_ptr<This>;  ///< shared_ptr to This
 | 
			
		||||
  using shared_ptr = std::shared_ptr<This>;  ///< shared_ptr to This
 | 
			
		||||
 | 
			
		||||
  using Values = gtsam::Values;  ///< backwards compatibility
 | 
			
		||||
  using Indices = KeyVector;     ///< map from keys to values
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -89,7 +89,7 @@ void HybridGaussianISAM::updateInternal(
 | 
			
		|||
 | 
			
		||||
  // Add the orphaned subtrees
 | 
			
		||||
  for (const sharedClique& orphan : *orphans) {
 | 
			
		||||
    factors += boost::make_shared<BayesTreeOrphanWrapper<Node>>(orphan);
 | 
			
		||||
    factors += std::make_shared<BayesTreeOrphanWrapper<Node>>(orphan);
 | 
			
		||||
  }
 | 
			
		||||
 | 
			
		||||
  const VariableIndex index(factors);
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -37,7 +37,7 @@ class GTSAM_EXPORT HybridGaussianISAM : public ISAM<HybridBayesTree> {
 | 
			
		|||
 public:
 | 
			
		||||
  typedef ISAM<HybridBayesTree> Base;
 | 
			
		||||
  typedef HybridGaussianISAM This;
 | 
			
		||||
  typedef boost::shared_ptr<This> shared_ptr;
 | 
			
		||||
  typedef std::shared_ptr<This> shared_ptr;
 | 
			
		||||
 | 
			
		||||
  /// @name Standard Constructors
 | 
			
		||||
  /// @{
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -50,23 +50,23 @@ struct HybridConstructorTraversalData {
 | 
			
		|||
 | 
			
		||||
  // Pre-order visitor function
 | 
			
		||||
  static HybridConstructorTraversalData ConstructorTraversalVisitorPre(
 | 
			
		||||
      const boost::shared_ptr<HybridEliminationTree::Node>& node,
 | 
			
		||||
      const std::shared_ptr<HybridEliminationTree::Node>& node,
 | 
			
		||||
      HybridConstructorTraversalData& parentData) {
 | 
			
		||||
    // On the pre-order pass, before children have been visited, we just set up
 | 
			
		||||
    // a traversal data structure with its own JT node, and create a child
 | 
			
		||||
    // pointer in its parent.
 | 
			
		||||
    HybridConstructorTraversalData data =
 | 
			
		||||
        HybridConstructorTraversalData(&parentData);
 | 
			
		||||
    data.junctionTreeNode = boost::make_shared<Node>(node->key, node->factors);
 | 
			
		||||
    data.junctionTreeNode = std::make_shared<Node>(node->key, node->factors);
 | 
			
		||||
    parentData.junctionTreeNode->addChild(data.junctionTreeNode);
 | 
			
		||||
 | 
			
		||||
    // Add all the discrete keys in the hybrid factors to the current data
 | 
			
		||||
    for (const auto& f : node->factors) {
 | 
			
		||||
      if (auto hf = boost::dynamic_pointer_cast<HybridFactor>(f)) {
 | 
			
		||||
      if (auto hf = std::dynamic_pointer_cast<HybridFactor>(f)) {
 | 
			
		||||
        for (auto& k : hf->discreteKeys()) {
 | 
			
		||||
          data.discreteKeys.insert(k.first);
 | 
			
		||||
        }
 | 
			
		||||
      } else if (auto hf = boost::dynamic_pointer_cast<DecisionTreeFactor>(f)) {
 | 
			
		||||
      } else if (auto hf = std::dynamic_pointer_cast<DecisionTreeFactor>(f)) {
 | 
			
		||||
        for (auto& k : hf->discreteKeys()) {
 | 
			
		||||
          data.discreteKeys.insert(k.first);
 | 
			
		||||
        }
 | 
			
		||||
| 
						 | 
				
			
			@ -78,7 +78,7 @@ struct HybridConstructorTraversalData {
 | 
			
		|||
 | 
			
		||||
  // Post-order visitor function
 | 
			
		||||
  static void ConstructorTraversalVisitorPost(
 | 
			
		||||
      const boost::shared_ptr<HybridEliminationTree::Node>& node,
 | 
			
		||||
      const std::shared_ptr<HybridEliminationTree::Node>& node,
 | 
			
		||||
      const HybridConstructorTraversalData& data) {
 | 
			
		||||
    // In this post-order visitor, we combine the symbolic elimination results
 | 
			
		||||
    // from the elimination tree children and symbolically eliminate the current
 | 
			
		||||
| 
						 | 
				
			
			@ -162,7 +162,7 @@ HybridJunctionTree::HybridJunctionTree(
 | 
			
		|||
  typedef HybridConstructorTraversalData Data;
 | 
			
		||||
  Data rootData(0);
 | 
			
		||||
  rootData.junctionTreeNode =
 | 
			
		||||
      boost::make_shared<typename Base::Node>();  // Make a dummy node to gather
 | 
			
		||||
      std::make_shared<typename Base::Node>();  // Make a dummy node to gather
 | 
			
		||||
                                                  // the junction tree roots
 | 
			
		||||
  treeTraversal::DepthFirstForest(eliminationTree, rootData,
 | 
			
		||||
                                  Data::ConstructorTraversalVisitorPre,
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -56,7 +56,7 @@ class GTSAM_EXPORT HybridJunctionTree
 | 
			
		|||
  typedef JunctionTree<HybridBayesTree, HybridGaussianFactorGraph>
 | 
			
		||||
      Base;                                    ///< Base class
 | 
			
		||||
  typedef HybridJunctionTree This;             ///< This class
 | 
			
		||||
  typedef boost::shared_ptr<This> shared_ptr;  ///< Shared pointer to this class
 | 
			
		||||
  typedef std::shared_ptr<This> shared_ptr;  ///< Shared pointer to this class
 | 
			
		||||
 | 
			
		||||
  /**
 | 
			
		||||
   * Build the elimination tree of a factor graph using precomputed column
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -43,10 +43,10 @@ void HybridNonlinearFactorGraph::print(const std::string& s,
 | 
			
		|||
/* ************************************************************************* */
 | 
			
		||||
HybridGaussianFactorGraph::shared_ptr HybridNonlinearFactorGraph::linearize(
 | 
			
		||||
    const Values& continuousValues) const {
 | 
			
		||||
  using boost::dynamic_pointer_cast;
 | 
			
		||||
  using std::dynamic_pointer_cast;
 | 
			
		||||
 | 
			
		||||
  // create an empty linear FG
 | 
			
		||||
  auto linearFG = boost::make_shared<HybridGaussianFactorGraph>();
 | 
			
		||||
  auto linearFG = std::make_shared<HybridGaussianFactorGraph>();
 | 
			
		||||
 | 
			
		||||
  linearFG->reserve(size());
 | 
			
		||||
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -35,7 +35,7 @@ class GTSAM_EXPORT HybridNonlinearFactorGraph : public HybridFactorGraph {
 | 
			
		|||
 public:
 | 
			
		||||
  using Base = HybridFactorGraph;
 | 
			
		||||
  using This = HybridNonlinearFactorGraph;     ///< this class
 | 
			
		||||
  using shared_ptr = boost::shared_ptr<This>;  ///< shared_ptr to This
 | 
			
		||||
  using shared_ptr = std::shared_ptr<This>;  ///< shared_ptr to This
 | 
			
		||||
 | 
			
		||||
  using Values = gtsam::Values;  ///< backwards compatibility
 | 
			
		||||
  using Indices = KeyVector;     ///> map from keys to values
 | 
			
		||||
| 
						 | 
				
			
			@ -74,7 +74,7 @@ class GTSAM_EXPORT HybridNonlinearFactorGraph : public HybridFactorGraph {
 | 
			
		|||
   * @param continuousValues: Dictionary of continuous values.
 | 
			
		||||
   * @return HybridGaussianFactorGraph::shared_ptr
 | 
			
		||||
   */
 | 
			
		||||
  boost::shared_ptr<HybridGaussianFactorGraph> linearize(
 | 
			
		||||
  std::shared_ptr<HybridGaussianFactorGraph> linearize(
 | 
			
		||||
      const Values& continuousValues) const;
 | 
			
		||||
  /// @}
 | 
			
		||||
};
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -50,7 +50,7 @@ void HybridNonlinearISAM::update(const HybridNonlinearFactorGraph& newFactors,
 | 
			
		|||
    // TODO: optimize for whole config?
 | 
			
		||||
    linPoint_.insert(initialValues);
 | 
			
		||||
 | 
			
		||||
    boost::shared_ptr<HybridGaussianFactorGraph> linearizedNewFactors =
 | 
			
		||||
    std::shared_ptr<HybridGaussianFactorGraph> linearizedNewFactors =
 | 
			
		||||
        newFactors.linearize(linPoint_);
 | 
			
		||||
 | 
			
		||||
    // Update ISAM
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -42,7 +42,7 @@ void HybridSmoother::update(HybridGaussianFactorGraph graph,
 | 
			
		|||
        bayesNetFragment->prune(*maxNrLeaves);
 | 
			
		||||
    // Set the bayes net fragment to the pruned version
 | 
			
		||||
    bayesNetFragment =
 | 
			
		||||
        boost::make_shared<HybridBayesNet>(prunedBayesNetFragment);
 | 
			
		||||
        std::make_shared<HybridBayesNet>(prunedBayesNetFragment);
 | 
			
		||||
  }
 | 
			
		||||
 | 
			
		||||
  // Add the partial bayes net to the posterior bayes net.
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -49,8 +49,8 @@ class MixtureFactor : public HybridFactor {
 | 
			
		|||
 public:
 | 
			
		||||
  using Base = HybridFactor;
 | 
			
		||||
  using This = MixtureFactor;
 | 
			
		||||
  using shared_ptr = boost::shared_ptr<MixtureFactor>;
 | 
			
		||||
  using sharedFactor = boost::shared_ptr<NonlinearFactor>;
 | 
			
		||||
  using shared_ptr = std::shared_ptr<MixtureFactor>;
 | 
			
		||||
  using sharedFactor = std::shared_ptr<NonlinearFactor>;
 | 
			
		||||
 | 
			
		||||
  /**
 | 
			
		||||
   * @brief typedef for DecisionTree which has Keys as node labels and
 | 
			
		||||
| 
						 | 
				
			
			@ -97,7 +97,7 @@ class MixtureFactor : public HybridFactor {
 | 
			
		|||
   */
 | 
			
		||||
  template <typename FACTOR>
 | 
			
		||||
  MixtureFactor(const KeyVector& keys, const DiscreteKeys& discreteKeys,
 | 
			
		||||
                const std::vector<boost::shared_ptr<FACTOR>>& factors,
 | 
			
		||||
                const std::vector<std::shared_ptr<FACTOR>>& factors,
 | 
			
		||||
                bool normalized = false)
 | 
			
		||||
      : Base(keys, discreteKeys), normalized_(normalized) {
 | 
			
		||||
    std::vector<NonlinearFactor::shared_ptr> nonlinear_factors;
 | 
			
		||||
| 
						 | 
				
			
			@ -108,7 +108,7 @@ class MixtureFactor : public HybridFactor {
 | 
			
		|||
      std::copy(f->keys().begin(), f->keys().end(),
 | 
			
		||||
                std::inserter(factor_keys_set, factor_keys_set.end()));
 | 
			
		||||
 | 
			
		||||
      if (auto nf = boost::dynamic_pointer_cast<NonlinearFactor>(f)) {
 | 
			
		||||
      if (auto nf = std::dynamic_pointer_cast<NonlinearFactor>(f)) {
 | 
			
		||||
        nonlinear_factors.push_back(nf);
 | 
			
		||||
      } else {
 | 
			
		||||
        throw std::runtime_error(
 | 
			
		||||
| 
						 | 
				
			
			@ -237,7 +237,7 @@ class MixtureFactor : public HybridFactor {
 | 
			
		|||
  }
 | 
			
		||||
 | 
			
		||||
  /// Linearize all the continuous factors to get a GaussianMixtureFactor.
 | 
			
		||||
  boost::shared_ptr<GaussianMixtureFactor> linearize(
 | 
			
		||||
  std::shared_ptr<GaussianMixtureFactor> linearize(
 | 
			
		||||
      const Values& continuousValues) const {
 | 
			
		||||
    // functional to linearize each factor in the decision tree
 | 
			
		||||
    auto linearizeDT = [continuousValues](const sharedFactor& factor) {
 | 
			
		||||
| 
						 | 
				
			
			@ -247,7 +247,7 @@ class MixtureFactor : public HybridFactor {
 | 
			
		|||
    DecisionTree<Key, GaussianFactor::shared_ptr> linearized_factors(
 | 
			
		||||
        factors_, linearizeDT);
 | 
			
		||||
 | 
			
		||||
    return boost::make_shared<GaussianMixtureFactor>(
 | 
			
		||||
    return std::make_shared<GaussianMixtureFactor>(
 | 
			
		||||
        continuousKeys_, discreteKeys_, linearized_factors);
 | 
			
		||||
  }
 | 
			
		||||
 | 
			
		||||
| 
						 | 
				
			
			@ -266,13 +266,13 @@ class MixtureFactor : public HybridFactor {
 | 
			
		|||
    // If this is a NoiseModelFactor, we'll use its noiseModel to
 | 
			
		||||
    // otherwise noiseModelFactor will be nullptr
 | 
			
		||||
    if (auto noiseModelFactor =
 | 
			
		||||
            boost::dynamic_pointer_cast<NoiseModelFactor>(factor)) {
 | 
			
		||||
            std::dynamic_pointer_cast<NoiseModelFactor>(factor)) {
 | 
			
		||||
      // If dynamic cast to NoiseModelFactor succeeded, see if the noise model
 | 
			
		||||
      // is Gaussian
 | 
			
		||||
      auto noiseModel = noiseModelFactor->noiseModel();
 | 
			
		||||
 | 
			
		||||
      auto gaussianNoiseModel =
 | 
			
		||||
          boost::dynamic_pointer_cast<noiseModel::Gaussian>(noiseModel);
 | 
			
		||||
          std::dynamic_pointer_cast<noiseModel::Gaussian>(noiseModel);
 | 
			
		||||
      if (gaussianNoiseModel) {
 | 
			
		||||
        // If the noise model is Gaussian, retrieve the information matrix
 | 
			
		||||
        infoMat = gaussianNoiseModel->information();
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -59,9 +59,9 @@ inline HybridGaussianFactorGraph::shared_ptr makeSwitchingChain(
 | 
			
		|||
  for (size_t t = 1; t < n; t++) {
 | 
			
		||||
    hfg.add(GaussianMixtureFactor(
 | 
			
		||||
        {keyFunc(t), keyFunc(t + 1)}, {{dKeyFunc(t), 2}},
 | 
			
		||||
        {boost::make_shared<JacobianFactor>(keyFunc(t), I_3x3, keyFunc(t + 1),
 | 
			
		||||
        {std::make_shared<JacobianFactor>(keyFunc(t), I_3x3, keyFunc(t + 1),
 | 
			
		||||
                                            I_3x3, Z_3x1),
 | 
			
		||||
         boost::make_shared<JacobianFactor>(keyFunc(t), I_3x3, keyFunc(t + 1),
 | 
			
		||||
         std::make_shared<JacobianFactor>(keyFunc(t), I_3x3, keyFunc(t + 1),
 | 
			
		||||
                                            I_3x3, Vector3::Ones())}));
 | 
			
		||||
 | 
			
		||||
    if (t > 1) {
 | 
			
		||||
| 
						 | 
				
			
			@ -70,7 +70,7 @@ inline HybridGaussianFactorGraph::shared_ptr makeSwitchingChain(
 | 
			
		|||
    }
 | 
			
		||||
  }
 | 
			
		||||
 | 
			
		||||
  return boost::make_shared<HybridGaussianFactorGraph>(std::move(hfg));
 | 
			
		||||
  return std::make_shared<HybridGaussianFactorGraph>(std::move(hfg));
 | 
			
		||||
}
 | 
			
		||||
 | 
			
		||||
/**
 | 
			
		||||
| 
						 | 
				
			
			@ -161,7 +161,7 @@ struct Switching {
 | 
			
		|||
      auto motion_models = motionModels(k, between_sigma);
 | 
			
		||||
      std::vector<NonlinearFactor::shared_ptr> components;
 | 
			
		||||
      for (auto &&f : motion_models) {
 | 
			
		||||
        components.push_back(boost::dynamic_pointer_cast<NonlinearFactor>(f));
 | 
			
		||||
        components.push_back(std::dynamic_pointer_cast<NonlinearFactor>(f));
 | 
			
		||||
      }
 | 
			
		||||
      nonlinearFactorGraph.emplace_shared<MixtureFactor>(
 | 
			
		||||
          keys, DiscreteKeys{modes[k]}, components);
 | 
			
		||||
| 
						 | 
				
			
			@ -192,9 +192,9 @@ struct Switching {
 | 
			
		|||
                                                           double sigma = 1.0) {
 | 
			
		||||
    auto noise_model = noiseModel::Isotropic::Sigma(1, sigma);
 | 
			
		||||
    auto still =
 | 
			
		||||
             boost::make_shared<MotionModel>(X(k), X(k + 1), 0.0, noise_model),
 | 
			
		||||
             std::make_shared<MotionModel>(X(k), X(k + 1), 0.0, noise_model),
 | 
			
		||||
         moving =
 | 
			
		||||
             boost::make_shared<MotionModel>(X(k), X(k + 1), 1.0, noise_model);
 | 
			
		||||
             std::make_shared<MotionModel>(X(k), X(k + 1), 1.0, noise_model);
 | 
			
		||||
    return {still, moving};
 | 
			
		||||
  }
 | 
			
		||||
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -185,7 +185,7 @@ TEST(GaussianMixture, Likelihood2) {
 | 
			
		|||
  {
 | 
			
		||||
    // We have a JacobianFactor
 | 
			
		||||
    const auto gf1 = (*likelihood)(assignment1);
 | 
			
		||||
    const auto jf1 = boost::dynamic_pointer_cast<JacobianFactor>(gf1);
 | 
			
		||||
    const auto jf1 = std::dynamic_pointer_cast<JacobianFactor>(gf1);
 | 
			
		||||
    CHECK(jf1);
 | 
			
		||||
 | 
			
		||||
    // It has 2 rows, not 1!
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -58,11 +58,11 @@ TEST(GaussianMixtureFactor, Sum) {
 | 
			
		|||
  sigmas << 1, 2;
 | 
			
		||||
  auto model = noiseModel::Diagonal::Sigmas(sigmas, true);
 | 
			
		||||
 | 
			
		||||
  auto f10 = boost::make_shared<JacobianFactor>(X(1), A1, X(2), A2, b);
 | 
			
		||||
  auto f11 = boost::make_shared<JacobianFactor>(X(1), A1, X(2), A2, b);
 | 
			
		||||
  auto f20 = boost::make_shared<JacobianFactor>(X(1), A1, X(3), A3, b);
 | 
			
		||||
  auto f21 = boost::make_shared<JacobianFactor>(X(1), A1, X(3), A3, b);
 | 
			
		||||
  auto f22 = boost::make_shared<JacobianFactor>(X(1), A1, X(3), A3, b);
 | 
			
		||||
  auto f10 = std::make_shared<JacobianFactor>(X(1), A1, X(2), A2, b);
 | 
			
		||||
  auto f11 = std::make_shared<JacobianFactor>(X(1), A1, X(2), A2, b);
 | 
			
		||||
  auto f20 = std::make_shared<JacobianFactor>(X(1), A1, X(3), A3, b);
 | 
			
		||||
  auto f21 = std::make_shared<JacobianFactor>(X(1), A1, X(3), A3, b);
 | 
			
		||||
  auto f22 = std::make_shared<JacobianFactor>(X(1), A1, X(3), A3, b);
 | 
			
		||||
  std::vector<GaussianFactor::shared_ptr> factorsA{f10, f11};
 | 
			
		||||
  std::vector<GaussianFactor::shared_ptr> factorsB{f20, f21, f22};
 | 
			
		||||
 | 
			
		||||
| 
						 | 
				
			
			@ -98,8 +98,8 @@ TEST(GaussianMixtureFactor, Printing) {
 | 
			
		|||
  auto A1 = Matrix::Zero(2, 1);
 | 
			
		||||
  auto A2 = Matrix::Zero(2, 2);
 | 
			
		||||
  auto b = Matrix::Zero(2, 1);
 | 
			
		||||
  auto f10 = boost::make_shared<JacobianFactor>(X(1), A1, X(2), A2, b);
 | 
			
		||||
  auto f11 = boost::make_shared<JacobianFactor>(X(1), A1, X(2), A2, b);
 | 
			
		||||
  auto f10 = std::make_shared<JacobianFactor>(X(1), A1, X(2), A2, b);
 | 
			
		||||
  auto f11 = std::make_shared<JacobianFactor>(X(1), A1, X(2), A2, b);
 | 
			
		||||
  std::vector<GaussianFactor::shared_ptr> factors{f10, f11};
 | 
			
		||||
 | 
			
		||||
  GaussianMixtureFactor mixtureFactor({X(1), X(2)}, {m1}, factors);
 | 
			
		||||
| 
						 | 
				
			
			@ -145,7 +145,7 @@ TEST(GaussianMixtureFactor, GaussianMixture) {
 | 
			
		|||
  dKeys.emplace_back(M(0), 2);
 | 
			
		||||
  dKeys.emplace_back(M(1), 2);
 | 
			
		||||
 | 
			
		||||
  auto gaussians = boost::make_shared<GaussianConditional>();
 | 
			
		||||
  auto gaussians = std::make_shared<GaussianConditional>();
 | 
			
		||||
  GaussianMixture::Conditionals conditionals(gaussians);
 | 
			
		||||
  GaussianMixture gm({}, keys, dKeys, conditionals);
 | 
			
		||||
 | 
			
		||||
| 
						 | 
				
			
			@ -165,8 +165,8 @@ TEST(GaussianMixtureFactor, Error) {
 | 
			
		|||
 | 
			
		||||
  auto b = Vector2::Zero();
 | 
			
		||||
 | 
			
		||||
  auto f0 = boost::make_shared<JacobianFactor>(X(1), A01, X(2), A02, b);
 | 
			
		||||
  auto f1 = boost::make_shared<JacobianFactor>(X(1), A11, X(2), A12, b);
 | 
			
		||||
  auto f0 = std::make_shared<JacobianFactor>(X(1), A01, X(2), A02, b);
 | 
			
		||||
  auto f1 = std::make_shared<JacobianFactor>(X(1), A11, X(2), A12, b);
 | 
			
		||||
  std::vector<GaussianFactor::shared_ptr> factors{f0, f1};
 | 
			
		||||
 | 
			
		||||
  GaussianMixtureFactor mixtureFactor({X(1), X(2)}, {m1}, factors);
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -99,9 +99,9 @@ TEST(HybridBayesNet, evaluateHybrid) {
 | 
			
		|||
  const SharedDiagonal model0 = noiseModel::Diagonal::Sigmas(Vector1(2.0)),
 | 
			
		||||
                       model1 = noiseModel::Diagonal::Sigmas(Vector1(3.0));
 | 
			
		||||
 | 
			
		||||
  const auto conditional0 = boost::make_shared<GaussianConditional>(
 | 
			
		||||
  const auto conditional0 = std::make_shared<GaussianConditional>(
 | 
			
		||||
                 X(1), Vector1::Constant(5), I_1x1, model0),
 | 
			
		||||
             conditional1 = boost::make_shared<GaussianConditional>(
 | 
			
		||||
             conditional1 = std::make_shared<GaussianConditional>(
 | 
			
		||||
                 X(1), Vector1::Constant(2), I_1x1, model1);
 | 
			
		||||
 | 
			
		||||
  // Create hybrid Bayes net.
 | 
			
		||||
| 
						 | 
				
			
			@ -295,7 +295,7 @@ TEST(HybridBayesNet, UpdateDiscreteConditionals) {
 | 
			
		|||
  size_t maxNrLeaves = 3;
 | 
			
		||||
  auto discreteConditionals = posterior->discreteConditionals();
 | 
			
		||||
  const DecisionTreeFactor::shared_ptr prunedDecisionTree =
 | 
			
		||||
      boost::make_shared<DecisionTreeFactor>(
 | 
			
		||||
      std::make_shared<DecisionTreeFactor>(
 | 
			
		||||
          discreteConditionals->prune(maxNrLeaves));
 | 
			
		||||
 | 
			
		||||
  EXPECT_LONGS_EQUAL(maxNrLeaves + 2 /*2 zero leaves*/,
 | 
			
		||||
| 
						 | 
				
			
			@ -323,7 +323,7 @@ TEST(HybridBayesNet, UpdateDiscreteConditionals) {
 | 
			
		|||
  // Get the pruned discrete conditionals as an AlgebraicDecisionTree
 | 
			
		||||
  auto pruned_discrete_conditionals = posterior->at(4)->asDiscrete();
 | 
			
		||||
  auto discrete_conditional_tree =
 | 
			
		||||
      boost::dynamic_pointer_cast<DecisionTreeFactor::ADT>(
 | 
			
		||||
      std::dynamic_pointer_cast<DecisionTreeFactor::ADT>(
 | 
			
		||||
          pruned_discrete_conditionals);
 | 
			
		||||
 | 
			
		||||
  // The checker functor verifies the values for us.
 | 
			
		||||
| 
						 | 
				
			
			@ -337,9 +337,9 @@ TEST(HybridBayesNet, Sampling) {
 | 
			
		|||
 | 
			
		||||
  auto noise_model = noiseModel::Diagonal::Sigmas(Vector1(1.0));
 | 
			
		||||
  auto zero_motion =
 | 
			
		||||
      boost::make_shared<BetweenFactor<double>>(X(0), X(1), 0, noise_model);
 | 
			
		||||
      std::make_shared<BetweenFactor<double>>(X(0), X(1), 0, noise_model);
 | 
			
		||||
  auto one_motion =
 | 
			
		||||
      boost::make_shared<BetweenFactor<double>>(X(0), X(1), 1, noise_model);
 | 
			
		||||
      std::make_shared<BetweenFactor<double>>(X(0), X(1), 1, noise_model);
 | 
			
		||||
  std::vector<NonlinearFactor::shared_ptr> factors = {zero_motion, one_motion};
 | 
			
		||||
  nfg.emplace_shared<PriorFactor<double>>(X(0), 0.0, noise_model);
 | 
			
		||||
  nfg.emplace_shared<MixtureFactor>(
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -200,7 +200,7 @@ GaussianFactorGraph::shared_ptr specificModesFactorGraph(
 | 
			
		|||
  // Add "motion models".
 | 
			
		||||
  auto motion_noise_model = noiseModel::Isotropic::Sigma(1, between_sigma);
 | 
			
		||||
  for (size_t k = 0; k < K - 1; k++) {
 | 
			
		||||
    auto motion_model = boost::make_shared<MotionModel>(
 | 
			
		||||
    auto motion_model = std::make_shared<MotionModel>(
 | 
			
		||||
        X(k), X(k + 1), discrete_seq.at(k), motion_noise_model);
 | 
			
		||||
    graph.push_back(motion_model);
 | 
			
		||||
  }
 | 
			
		||||
| 
						 | 
				
			
			@ -256,7 +256,7 @@ AlgebraicDecisionTree<Key> getProbPrimeTree(
 | 
			
		|||
  vector<VectorValues::shared_ptr> vector_values;
 | 
			
		||||
  for (const DiscreteValues& assignment : assignments) {
 | 
			
		||||
    VectorValues values = bayesNet->optimize(assignment);
 | 
			
		||||
    vector_values.push_back(boost::make_shared<VectorValues>(values));
 | 
			
		||||
    vector_values.push_back(std::make_shared<VectorValues>(values));
 | 
			
		||||
  }
 | 
			
		||||
  DecisionTree<Key, VectorValues::shared_ptr> delta_tree(discrete_keys,
 | 
			
		||||
                                                         vector_values);
 | 
			
		||||
| 
						 | 
				
			
			@ -413,9 +413,9 @@ static HybridNonlinearFactorGraph createHybridNonlinearFactorGraph() {
 | 
			
		|||
  // Add mixture factor:
 | 
			
		||||
  DiscreteKey m(M(0), 2);
 | 
			
		||||
  const auto zero_motion =
 | 
			
		||||
      boost::make_shared<BetweenFactor<double>>(X(0), X(1), 0, noise_model);
 | 
			
		||||
      std::make_shared<BetweenFactor<double>>(X(0), X(1), 0, noise_model);
 | 
			
		||||
  const auto one_motion =
 | 
			
		||||
      boost::make_shared<BetweenFactor<double>>(X(0), X(1), 1, noise_model);
 | 
			
		||||
      std::make_shared<BetweenFactor<double>>(X(0), X(1), 1, noise_model);
 | 
			
		||||
  nfg.emplace_shared<MixtureFactor>(
 | 
			
		||||
      KeyVector{X(0), X(1)}, DiscreteKeys{m},
 | 
			
		||||
      std::vector<NonlinearFactor::shared_ptr>{zero_motion, one_motion});
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -73,9 +73,9 @@ TEST(HybridGaussianFactorGraph, Creation) {
 | 
			
		|||
  GaussianMixture gm({X(0)}, {X(1)}, DiscreteKeys(DiscreteKey{M(0), 2}),
 | 
			
		||||
                     GaussianMixture::Conditionals(
 | 
			
		||||
                         M(0),
 | 
			
		||||
                         boost::make_shared<GaussianConditional>(
 | 
			
		||||
                         std::make_shared<GaussianConditional>(
 | 
			
		||||
                             X(0), Z_3x1, I_3x3, X(1), I_3x3),
 | 
			
		||||
                         boost::make_shared<GaussianConditional>(
 | 
			
		||||
                         std::make_shared<GaussianConditional>(
 | 
			
		||||
                             X(0), Vector3::Ones(), I_3x3, X(1), I_3x3)));
 | 
			
		||||
  hfg.add(gm);
 | 
			
		||||
 | 
			
		||||
| 
						 | 
				
			
			@ -126,8 +126,8 @@ TEST(HybridGaussianFactorGraph, eliminateFullSequentialEqualChance) {
 | 
			
		|||
  // Add a gaussian mixture factor ϕ(x1, c1)
 | 
			
		||||
  DiscreteKey m1(M(1), 2);
 | 
			
		||||
  DecisionTree<Key, GaussianFactor::shared_ptr> dt(
 | 
			
		||||
      M(1), boost::make_shared<JacobianFactor>(X(1), I_3x3, Z_3x1),
 | 
			
		||||
      boost::make_shared<JacobianFactor>(X(1), I_3x3, Vector3::Ones()));
 | 
			
		||||
      M(1), std::make_shared<JacobianFactor>(X(1), I_3x3, Z_3x1),
 | 
			
		||||
      std::make_shared<JacobianFactor>(X(1), I_3x3, Vector3::Ones()));
 | 
			
		||||
  hfg.add(GaussianMixtureFactor({X(1)}, {m1}, dt));
 | 
			
		||||
 | 
			
		||||
  auto result = hfg.eliminateSequential();
 | 
			
		||||
| 
						 | 
				
			
			@ -152,8 +152,8 @@ TEST(HybridGaussianFactorGraph, eliminateFullSequentialSimple) {
 | 
			
		|||
  hfg.add(JacobianFactor(X(0), I_3x3, X(1), -I_3x3, Z_3x1));
 | 
			
		||||
 | 
			
		||||
  std::vector<GaussianFactor::shared_ptr> factors = {
 | 
			
		||||
      boost::make_shared<JacobianFactor>(X(1), I_3x3, Z_3x1),
 | 
			
		||||
      boost::make_shared<JacobianFactor>(X(1), I_3x3, Vector3::Ones())};
 | 
			
		||||
      std::make_shared<JacobianFactor>(X(1), I_3x3, Z_3x1),
 | 
			
		||||
      std::make_shared<JacobianFactor>(X(1), I_3x3, Vector3::Ones())};
 | 
			
		||||
  hfg.add(GaussianMixtureFactor({X(1)}, {m1}, factors));
 | 
			
		||||
 | 
			
		||||
  // Discrete probability table for c1
 | 
			
		||||
| 
						 | 
				
			
			@ -178,8 +178,8 @@ TEST(HybridGaussianFactorGraph, eliminateFullMultifrontalSimple) {
 | 
			
		|||
 | 
			
		||||
  hfg.add(GaussianMixtureFactor(
 | 
			
		||||
      {X(1)}, {{M(1), 2}},
 | 
			
		||||
      {boost::make_shared<JacobianFactor>(X(1), I_3x3, Z_3x1),
 | 
			
		||||
       boost::make_shared<JacobianFactor>(X(1), I_3x3, Vector3::Ones())}));
 | 
			
		||||
      {std::make_shared<JacobianFactor>(X(1), I_3x3, Z_3x1),
 | 
			
		||||
       std::make_shared<JacobianFactor>(X(1), I_3x3, Vector3::Ones())}));
 | 
			
		||||
 | 
			
		||||
  hfg.add(DecisionTreeFactor(m1, {2, 8}));
 | 
			
		||||
  // TODO(Varun) Adding extra discrete variable not connected to continuous
 | 
			
		||||
| 
						 | 
				
			
			@ -207,8 +207,8 @@ TEST(HybridGaussianFactorGraph, eliminateFullMultifrontalCLG) {
 | 
			
		|||
 | 
			
		||||
  // Decision tree with different modes on x1
 | 
			
		||||
  DecisionTree<Key, GaussianFactor::shared_ptr> dt(
 | 
			
		||||
      M(1), boost::make_shared<JacobianFactor>(X(1), I_3x3, Z_3x1),
 | 
			
		||||
      boost::make_shared<JacobianFactor>(X(1), I_3x3, Vector3::Ones()));
 | 
			
		||||
      M(1), std::make_shared<JacobianFactor>(X(1), I_3x3, Z_3x1),
 | 
			
		||||
      std::make_shared<JacobianFactor>(X(1), I_3x3, Vector3::Ones()));
 | 
			
		||||
 | 
			
		||||
  // Hybrid factor P(x1|c1)
 | 
			
		||||
  hfg.add(GaussianMixtureFactor({X(1)}, {m}, dt));
 | 
			
		||||
| 
						 | 
				
			
			@ -238,12 +238,12 @@ TEST(HybridGaussianFactorGraph, eliminateFullMultifrontalTwoClique) {
 | 
			
		|||
  {
 | 
			
		||||
    hfg.add(GaussianMixtureFactor(
 | 
			
		||||
        {X(0)}, {{M(0), 2}},
 | 
			
		||||
        {boost::make_shared<JacobianFactor>(X(0), I_3x3, Z_3x1),
 | 
			
		||||
         boost::make_shared<JacobianFactor>(X(0), I_3x3, Vector3::Ones())}));
 | 
			
		||||
        {std::make_shared<JacobianFactor>(X(0), I_3x3, Z_3x1),
 | 
			
		||||
         std::make_shared<JacobianFactor>(X(0), I_3x3, Vector3::Ones())}));
 | 
			
		||||
 | 
			
		||||
    DecisionTree<Key, GaussianFactor::shared_ptr> dt1(
 | 
			
		||||
        M(1), boost::make_shared<JacobianFactor>(X(2), I_3x3, Z_3x1),
 | 
			
		||||
        boost::make_shared<JacobianFactor>(X(2), I_3x3, Vector3::Ones()));
 | 
			
		||||
        M(1), std::make_shared<JacobianFactor>(X(2), I_3x3, Z_3x1),
 | 
			
		||||
        std::make_shared<JacobianFactor>(X(2), I_3x3, Vector3::Ones()));
 | 
			
		||||
 | 
			
		||||
    hfg.add(GaussianMixtureFactor({X(2)}, {{M(1), 2}}, dt1));
 | 
			
		||||
  }
 | 
			
		||||
| 
						 | 
				
			
			@ -255,14 +255,14 @@ TEST(HybridGaussianFactorGraph, eliminateFullMultifrontalTwoClique) {
 | 
			
		|||
 | 
			
		||||
  {
 | 
			
		||||
    DecisionTree<Key, GaussianFactor::shared_ptr> dt(
 | 
			
		||||
        M(3), boost::make_shared<JacobianFactor>(X(3), I_3x3, Z_3x1),
 | 
			
		||||
        boost::make_shared<JacobianFactor>(X(3), I_3x3, Vector3::Ones()));
 | 
			
		||||
        M(3), std::make_shared<JacobianFactor>(X(3), I_3x3, Z_3x1),
 | 
			
		||||
        std::make_shared<JacobianFactor>(X(3), I_3x3, Vector3::Ones()));
 | 
			
		||||
 | 
			
		||||
    hfg.add(GaussianMixtureFactor({X(3)}, {{M(3), 2}}, dt));
 | 
			
		||||
 | 
			
		||||
    DecisionTree<Key, GaussianFactor::shared_ptr> dt1(
 | 
			
		||||
        M(2), boost::make_shared<JacobianFactor>(X(5), I_3x3, Z_3x1),
 | 
			
		||||
        boost::make_shared<JacobianFactor>(X(5), I_3x3, Vector3::Ones()));
 | 
			
		||||
        M(2), std::make_shared<JacobianFactor>(X(5), I_3x3, Z_3x1),
 | 
			
		||||
        std::make_shared<JacobianFactor>(X(5), I_3x3, Vector3::Ones()));
 | 
			
		||||
 | 
			
		||||
    hfg.add(GaussianMixtureFactor({X(5)}, {{M(2), 2}}, dt1));
 | 
			
		||||
  }
 | 
			
		||||
| 
						 | 
				
			
			@ -510,8 +510,8 @@ TEST(HybridGaussianFactorGraph, optimize) {
 | 
			
		|||
  hfg.add(JacobianFactor(X(0), I_3x3, X(1), -I_3x3, Z_3x1));
 | 
			
		||||
 | 
			
		||||
  DecisionTree<Key, GaussianFactor::shared_ptr> dt(
 | 
			
		||||
      C(1), boost::make_shared<JacobianFactor>(X(1), I_3x3, Z_3x1),
 | 
			
		||||
      boost::make_shared<JacobianFactor>(X(1), I_3x3, Vector3::Ones()));
 | 
			
		||||
      C(1), std::make_shared<JacobianFactor>(X(1), I_3x3, Z_3x1),
 | 
			
		||||
      std::make_shared<JacobianFactor>(X(1), I_3x3, Vector3::Ones()));
 | 
			
		||||
 | 
			
		||||
  hfg.add(GaussianMixtureFactor({X(1)}, {c1}, dt));
 | 
			
		||||
 | 
			
		||||
| 
						 | 
				
			
			@ -624,11 +624,11 @@ TEST(HybridGaussianFactorGraph, assembleGraphTree) {
 | 
			
		|||
  // Create expected decision tree with two factor graphs:
 | 
			
		||||
 | 
			
		||||
  // Get mixture factor:
 | 
			
		||||
  auto mixture = boost::dynamic_pointer_cast<GaussianMixtureFactor>(fg.at(0));
 | 
			
		||||
  auto mixture = std::dynamic_pointer_cast<GaussianMixtureFactor>(fg.at(0));
 | 
			
		||||
  CHECK(mixture);
 | 
			
		||||
 | 
			
		||||
  // Get prior factor:
 | 
			
		||||
  const auto gf = boost::dynamic_pointer_cast<HybridConditional>(fg.at(1));
 | 
			
		||||
  const auto gf = std::dynamic_pointer_cast<HybridConditional>(fg.at(1));
 | 
			
		||||
  CHECK(gf);
 | 
			
		||||
  using GF = GaussianFactor::shared_ptr;
 | 
			
		||||
  const GF prior = gf->asGaussian();
 | 
			
		||||
| 
						 | 
				
			
			@ -709,9 +709,9 @@ TEST(HybridGaussianFactorGraph, EliminateTiny1) {
 | 
			
		|||
  // Create Gaussian mixture on X(0).
 | 
			
		||||
  using tiny::mode;
 | 
			
		||||
  // regression, but mean checked to be 5.0 in both cases:
 | 
			
		||||
  const auto conditional0 = boost::make_shared<GaussianConditional>(
 | 
			
		||||
  const auto conditional0 = std::make_shared<GaussianConditional>(
 | 
			
		||||
                 X(0), Vector1(14.1421), I_1x1 * 2.82843),
 | 
			
		||||
             conditional1 = boost::make_shared<GaussianConditional>(
 | 
			
		||||
             conditional1 = std::make_shared<GaussianConditional>(
 | 
			
		||||
                 X(0), Vector1(10.1379), I_1x1 * 2.02759);
 | 
			
		||||
  expectedBayesNet.emplace_back(
 | 
			
		||||
      new GaussianMixture({X(0)}, {}, {mode}, {conditional0, conditional1}));
 | 
			
		||||
| 
						 | 
				
			
			@ -743,9 +743,9 @@ TEST(HybridGaussianFactorGraph, EliminateTiny2) {
 | 
			
		|||
  // Create Gaussian mixture on X(0).
 | 
			
		||||
  using tiny::mode;
 | 
			
		||||
  // regression, but mean checked to be 5.0 in both cases:
 | 
			
		||||
  const auto conditional0 = boost::make_shared<GaussianConditional>(
 | 
			
		||||
  const auto conditional0 = std::make_shared<GaussianConditional>(
 | 
			
		||||
                 X(0), Vector1(17.3205), I_1x1 * 3.4641),
 | 
			
		||||
             conditional1 = boost::make_shared<GaussianConditional>(
 | 
			
		||||
             conditional1 = std::make_shared<GaussianConditional>(
 | 
			
		||||
                 X(0), Vector1(10.274), I_1x1 * 2.0548);
 | 
			
		||||
  expectedBayesNet.emplace_back(
 | 
			
		||||
      new GaussianMixture({X(0)}, {}, {mode}, {conditional0, conditional1}));
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -201,7 +201,7 @@ TEST(HybridGaussianElimination, IncrementalInference) {
 | 
			
		|||
  DiscreteKeys discrete_keys = {{M(0), 2}, {M(1), 2}};
 | 
			
		||||
  vector<double> probs = {0.095292197, 0.31417524, 0.28275772, 0.30777485};
 | 
			
		||||
  auto expectedConditional =
 | 
			
		||||
      boost::make_shared<DecisionTreeFactor>(discrete_keys, probs);
 | 
			
		||||
      std::make_shared<DecisionTreeFactor>(discrete_keys, probs);
 | 
			
		||||
  EXPECT(assert_equal(*expectedConditional, *actualConditional, 1e-6));
 | 
			
		||||
}
 | 
			
		||||
 | 
			
		||||
| 
						 | 
				
			
			@ -422,12 +422,12 @@ TEST(HybridGaussianISAM, NonTrivial) {
 | 
			
		|||
  Pose2 odometry(1.0, 0.0, 0.0);
 | 
			
		||||
  KeyVector contKeys = {W(0), W(1)};
 | 
			
		||||
  auto noise_model = noiseModel::Isotropic::Sigma(3, 1.0);
 | 
			
		||||
  auto still = boost::make_shared<PlanarMotionModel>(W(0), W(1), Pose2(0, 0, 0),
 | 
			
		||||
  auto still = std::make_shared<PlanarMotionModel>(W(0), W(1), Pose2(0, 0, 0),
 | 
			
		||||
                                                     noise_model),
 | 
			
		||||
       moving = boost::make_shared<PlanarMotionModel>(W(0), W(1), odometry,
 | 
			
		||||
       moving = std::make_shared<PlanarMotionModel>(W(0), W(1), odometry,
 | 
			
		||||
                                                      noise_model);
 | 
			
		||||
  std::vector<PlanarMotionModel::shared_ptr> components = {moving, still};
 | 
			
		||||
  auto mixtureFactor = boost::make_shared<MixtureFactor>(
 | 
			
		||||
  auto mixtureFactor = std::make_shared<MixtureFactor>(
 | 
			
		||||
      contKeys, DiscreteKeys{gtsam::DiscreteKey(M(1), 2)}, components);
 | 
			
		||||
  fg.push_back(mixtureFactor);
 | 
			
		||||
 | 
			
		||||
| 
						 | 
				
			
			@ -462,12 +462,12 @@ TEST(HybridGaussianISAM, NonTrivial) {
 | 
			
		|||
  /*************** Run Round 3 ***************/
 | 
			
		||||
  // Add odometry factor with discrete modes.
 | 
			
		||||
  contKeys = {W(1), W(2)};
 | 
			
		||||
  still = boost::make_shared<PlanarMotionModel>(W(1), W(2), Pose2(0, 0, 0),
 | 
			
		||||
  still = std::make_shared<PlanarMotionModel>(W(1), W(2), Pose2(0, 0, 0),
 | 
			
		||||
                                                noise_model);
 | 
			
		||||
  moving =
 | 
			
		||||
      boost::make_shared<PlanarMotionModel>(W(1), W(2), odometry, noise_model);
 | 
			
		||||
      std::make_shared<PlanarMotionModel>(W(1), W(2), odometry, noise_model);
 | 
			
		||||
  components = {moving, still};
 | 
			
		||||
  mixtureFactor = boost::make_shared<MixtureFactor>(
 | 
			
		||||
  mixtureFactor = std::make_shared<MixtureFactor>(
 | 
			
		||||
      contKeys, DiscreteKeys{gtsam::DiscreteKey(M(2), 2)}, components);
 | 
			
		||||
  fg.push_back(mixtureFactor);
 | 
			
		||||
 | 
			
		||||
| 
						 | 
				
			
			@ -505,12 +505,12 @@ TEST(HybridGaussianISAM, NonTrivial) {
 | 
			
		|||
  /*************** Run Round 4 ***************/
 | 
			
		||||
  // Add odometry factor with discrete modes.
 | 
			
		||||
  contKeys = {W(2), W(3)};
 | 
			
		||||
  still = boost::make_shared<PlanarMotionModel>(W(2), W(3), Pose2(0, 0, 0),
 | 
			
		||||
  still = std::make_shared<PlanarMotionModel>(W(2), W(3), Pose2(0, 0, 0),
 | 
			
		||||
                                                noise_model);
 | 
			
		||||
  moving =
 | 
			
		||||
      boost::make_shared<PlanarMotionModel>(W(2), W(3), odometry, noise_model);
 | 
			
		||||
      std::make_shared<PlanarMotionModel>(W(2), W(3), odometry, noise_model);
 | 
			
		||||
  components = {moving, still};
 | 
			
		||||
  mixtureFactor = boost::make_shared<MixtureFactor>(
 | 
			
		||||
  mixtureFactor = std::make_shared<MixtureFactor>(
 | 
			
		||||
      contKeys, DiscreteKeys{gtsam::DiscreteKey(M(3), 2)}, components);
 | 
			
		||||
  fg.push_back(mixtureFactor);
 | 
			
		||||
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -80,12 +80,12 @@ TEST(HybridNonlinearFactorGraph, Equals) {
 | 
			
		|||
  // Test empty factor graphs
 | 
			
		||||
  EXPECT(assert_equal(graph1, graph2));
 | 
			
		||||
 | 
			
		||||
  auto f0 = boost::make_shared<PriorFactor<Pose2>>(
 | 
			
		||||
  auto f0 = std::make_shared<PriorFactor<Pose2>>(
 | 
			
		||||
      1, Pose2(), noiseModel::Isotropic::Sigma(3, 0.001));
 | 
			
		||||
  graph1.push_back(f0);
 | 
			
		||||
  graph2.push_back(f0);
 | 
			
		||||
 | 
			
		||||
  auto f1 = boost::make_shared<BetweenFactor<Pose2>>(
 | 
			
		||||
  auto f1 = std::make_shared<BetweenFactor<Pose2>>(
 | 
			
		||||
      1, 2, Pose2(), noiseModel::Isotropic::Sigma(3, 0.1));
 | 
			
		||||
  graph1.push_back(f1);
 | 
			
		||||
  graph2.push_back(f1);
 | 
			
		||||
| 
						 | 
				
			
			@ -99,13 +99,13 @@ TEST(HybridNonlinearFactorGraph, Equals) {
 | 
			
		|||
 */
 | 
			
		||||
TEST(HybridNonlinearFactorGraph, Resize) {
 | 
			
		||||
  HybridNonlinearFactorGraph fg;
 | 
			
		||||
  auto nonlinearFactor = boost::make_shared<BetweenFactor<double>>();
 | 
			
		||||
  auto nonlinearFactor = std::make_shared<BetweenFactor<double>>();
 | 
			
		||||
  fg.push_back(nonlinearFactor);
 | 
			
		||||
 | 
			
		||||
  auto discreteFactor = boost::make_shared<DecisionTreeFactor>();
 | 
			
		||||
  auto discreteFactor = std::make_shared<DecisionTreeFactor>();
 | 
			
		||||
  fg.push_back(discreteFactor);
 | 
			
		||||
 | 
			
		||||
  auto dcFactor = boost::make_shared<MixtureFactor>();
 | 
			
		||||
  auto dcFactor = std::make_shared<MixtureFactor>();
 | 
			
		||||
  fg.push_back(dcFactor);
 | 
			
		||||
 | 
			
		||||
  EXPECT_LONGS_EQUAL(fg.size(), 3);
 | 
			
		||||
| 
						 | 
				
			
			@ -120,19 +120,19 @@ TEST(HybridNonlinearFactorGraph, Resize) {
 | 
			
		|||
 */
 | 
			
		||||
TEST(HybridGaussianFactorGraph, Resize) {
 | 
			
		||||
  HybridNonlinearFactorGraph nhfg;
 | 
			
		||||
  auto nonlinearFactor = boost::make_shared<BetweenFactor<double>>(
 | 
			
		||||
  auto nonlinearFactor = std::make_shared<BetweenFactor<double>>(
 | 
			
		||||
      X(0), X(1), 0.0, Isotropic::Sigma(1, 0.1));
 | 
			
		||||
  nhfg.push_back(nonlinearFactor);
 | 
			
		||||
  auto discreteFactor = boost::make_shared<DecisionTreeFactor>();
 | 
			
		||||
  auto discreteFactor = std::make_shared<DecisionTreeFactor>();
 | 
			
		||||
  nhfg.push_back(discreteFactor);
 | 
			
		||||
 | 
			
		||||
  KeyVector contKeys = {X(0), X(1)};
 | 
			
		||||
  auto noise_model = noiseModel::Isotropic::Sigma(1, 1.0);
 | 
			
		||||
  auto still = boost::make_shared<MotionModel>(X(0), X(1), 0.0, noise_model),
 | 
			
		||||
       moving = boost::make_shared<MotionModel>(X(0), X(1), 1.0, noise_model);
 | 
			
		||||
  auto still = std::make_shared<MotionModel>(X(0), X(1), 0.0, noise_model),
 | 
			
		||||
       moving = std::make_shared<MotionModel>(X(0), X(1), 1.0, noise_model);
 | 
			
		||||
 | 
			
		||||
  std::vector<MotionModel::shared_ptr> components = {still, moving};
 | 
			
		||||
  auto dcFactor = boost::make_shared<MixtureFactor>(
 | 
			
		||||
  auto dcFactor = std::make_shared<MixtureFactor>(
 | 
			
		||||
      contKeys, DiscreteKeys{gtsam::DiscreteKey(M(1), 2)}, components);
 | 
			
		||||
  nhfg.push_back(dcFactor);
 | 
			
		||||
 | 
			
		||||
| 
						 | 
				
			
			@ -154,24 +154,24 @@ TEST(HybridGaussianFactorGraph, Resize) {
 | 
			
		|||
 * keys provided do not match the keys in the factors.
 | 
			
		||||
 */
 | 
			
		||||
TEST(HybridGaussianFactorGraph, MixtureFactor) {
 | 
			
		||||
  auto nonlinearFactor = boost::make_shared<BetweenFactor<double>>(
 | 
			
		||||
  auto nonlinearFactor = std::make_shared<BetweenFactor<double>>(
 | 
			
		||||
      X(0), X(1), 0.0, Isotropic::Sigma(1, 0.1));
 | 
			
		||||
  auto discreteFactor = boost::make_shared<DecisionTreeFactor>();
 | 
			
		||||
  auto discreteFactor = std::make_shared<DecisionTreeFactor>();
 | 
			
		||||
 | 
			
		||||
  auto noise_model = noiseModel::Isotropic::Sigma(1, 1.0);
 | 
			
		||||
  auto still = boost::make_shared<MotionModel>(X(0), X(1), 0.0, noise_model),
 | 
			
		||||
       moving = boost::make_shared<MotionModel>(X(0), X(1), 1.0, noise_model);
 | 
			
		||||
  auto still = std::make_shared<MotionModel>(X(0), X(1), 0.0, noise_model),
 | 
			
		||||
       moving = std::make_shared<MotionModel>(X(0), X(1), 1.0, noise_model);
 | 
			
		||||
 | 
			
		||||
  std::vector<MotionModel::shared_ptr> components = {still, moving};
 | 
			
		||||
 | 
			
		||||
  // Check for exception when number of continuous keys are under-specified.
 | 
			
		||||
  KeyVector contKeys = {X(0)};
 | 
			
		||||
  THROWS_EXCEPTION(boost::make_shared<MixtureFactor>(
 | 
			
		||||
  THROWS_EXCEPTION(std::make_shared<MixtureFactor>(
 | 
			
		||||
      contKeys, DiscreteKeys{gtsam::DiscreteKey(M(1), 2)}, components));
 | 
			
		||||
 | 
			
		||||
  // Check for exception when number of continuous keys are too many.
 | 
			
		||||
  contKeys = {X(0), X(1), X(2)};
 | 
			
		||||
  THROWS_EXCEPTION(boost::make_shared<MixtureFactor>(
 | 
			
		||||
  THROWS_EXCEPTION(std::make_shared<MixtureFactor>(
 | 
			
		||||
      contKeys, DiscreteKeys{gtsam::DiscreteKey(M(1), 2)}, components));
 | 
			
		||||
}
 | 
			
		||||
 | 
			
		||||
| 
						 | 
				
			
			@ -181,21 +181,21 @@ TEST(HybridGaussianFactorGraph, MixtureFactor) {
 | 
			
		|||
TEST(HybridFactorGraph, PushBack) {
 | 
			
		||||
  HybridNonlinearFactorGraph fg;
 | 
			
		||||
 | 
			
		||||
  auto nonlinearFactor = boost::make_shared<BetweenFactor<double>>();
 | 
			
		||||
  auto nonlinearFactor = std::make_shared<BetweenFactor<double>>();
 | 
			
		||||
  fg.push_back(nonlinearFactor);
 | 
			
		||||
 | 
			
		||||
  EXPECT_LONGS_EQUAL(fg.size(), 1);
 | 
			
		||||
 | 
			
		||||
  fg = HybridNonlinearFactorGraph();
 | 
			
		||||
 | 
			
		||||
  auto discreteFactor = boost::make_shared<DecisionTreeFactor>();
 | 
			
		||||
  auto discreteFactor = std::make_shared<DecisionTreeFactor>();
 | 
			
		||||
  fg.push_back(discreteFactor);
 | 
			
		||||
 | 
			
		||||
  EXPECT_LONGS_EQUAL(fg.size(), 1);
 | 
			
		||||
 | 
			
		||||
  fg = HybridNonlinearFactorGraph();
 | 
			
		||||
 | 
			
		||||
  auto dcFactor = boost::make_shared<MixtureFactor>();
 | 
			
		||||
  auto dcFactor = std::make_shared<MixtureFactor>();
 | 
			
		||||
  fg.push_back(dcFactor);
 | 
			
		||||
 | 
			
		||||
  EXPECT_LONGS_EQUAL(fg.size(), 1);
 | 
			
		||||
| 
						 | 
				
			
			@ -203,7 +203,7 @@ TEST(HybridFactorGraph, PushBack) {
 | 
			
		|||
  // Now do the same with HybridGaussianFactorGraph
 | 
			
		||||
  HybridGaussianFactorGraph ghfg;
 | 
			
		||||
 | 
			
		||||
  auto gaussianFactor = boost::make_shared<JacobianFactor>();
 | 
			
		||||
  auto gaussianFactor = std::make_shared<JacobianFactor>();
 | 
			
		||||
  ghfg.push_back(gaussianFactor);
 | 
			
		||||
 | 
			
		||||
  EXPECT_LONGS_EQUAL(ghfg.size(), 1);
 | 
			
		||||
| 
						 | 
				
			
			@ -329,7 +329,7 @@ GaussianFactorGraph::shared_ptr batchGFG(double between,
 | 
			
		|||
  NonlinearFactorGraph graph;
 | 
			
		||||
  graph.addPrior<double>(X(0), 0, Isotropic::Sigma(1, 0.1));
 | 
			
		||||
 | 
			
		||||
  auto between_x0_x1 = boost::make_shared<MotionModel>(
 | 
			
		||||
  auto between_x0_x1 = std::make_shared<MotionModel>(
 | 
			
		||||
      X(0), X(1), between, Isotropic::Sigma(1, 1.0));
 | 
			
		||||
 | 
			
		||||
  graph.push_back(between_x0_x1);
 | 
			
		||||
| 
						 | 
				
			
			@ -351,7 +351,7 @@ TEST(HybridGaussianElimination, EliminateHybrid_2_Variable) {
 | 
			
		|||
  ordering += X(1);
 | 
			
		||||
 | 
			
		||||
  HybridConditional::shared_ptr hybridConditionalMixture;
 | 
			
		||||
  boost::shared_ptr<Factor> factorOnModes;
 | 
			
		||||
  std::shared_ptr<Factor> factorOnModes;
 | 
			
		||||
 | 
			
		||||
  std::tie(hybridConditionalMixture, factorOnModes) =
 | 
			
		||||
      EliminateHybrid(factors, ordering);
 | 
			
		||||
| 
						 | 
				
			
			@ -684,9 +684,9 @@ TEST(HybridFactorGraph, DefaultDecisionTree) {
 | 
			
		|||
  Pose2 odometry(2.0, 0.0, 0.0);
 | 
			
		||||
  KeyVector contKeys = {X(0), X(1)};
 | 
			
		||||
  auto noise_model = noiseModel::Isotropic::Sigma(3, 1.0);
 | 
			
		||||
  auto still = boost::make_shared<PlanarMotionModel>(X(0), X(1), Pose2(0, 0, 0),
 | 
			
		||||
  auto still = std::make_shared<PlanarMotionModel>(X(0), X(1), Pose2(0, 0, 0),
 | 
			
		||||
                                                     noise_model),
 | 
			
		||||
       moving = boost::make_shared<PlanarMotionModel>(X(0), X(1), odometry,
 | 
			
		||||
       moving = std::make_shared<PlanarMotionModel>(X(0), X(1), odometry,
 | 
			
		||||
                                                      noise_model);
 | 
			
		||||
  std::vector<PlanarMotionModel::shared_ptr> motion_models = {still, moving};
 | 
			
		||||
  fg.emplace_shared<MixtureFactor>(
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -218,7 +218,7 @@ TEST(HybridNonlinearISAM, IncrementalInference) {
 | 
			
		|||
  DiscreteKeys discrete_keys = {{M(0), 2}, {M(1), 2}};
 | 
			
		||||
  vector<double> probs = {0.095292197, 0.31417524, 0.28275772, 0.30777485};
 | 
			
		||||
  auto expectedConditional =
 | 
			
		||||
      boost::make_shared<DecisionTreeFactor>(discrete_keys, probs);
 | 
			
		||||
      std::make_shared<DecisionTreeFactor>(discrete_keys, probs);
 | 
			
		||||
  EXPECT(assert_equal(*expectedConditional, *actualConditional, 1e-6));
 | 
			
		||||
}
 | 
			
		||||
 | 
			
		||||
| 
						 | 
				
			
			@ -441,12 +441,12 @@ TEST(HybridNonlinearISAM, NonTrivial) {
 | 
			
		|||
  Pose2 odometry(1.0, 0.0, 0.0);
 | 
			
		||||
  KeyVector contKeys = {W(0), W(1)};
 | 
			
		||||
  auto noise_model = noiseModel::Isotropic::Sigma(3, 1.0);
 | 
			
		||||
  auto still = boost::make_shared<PlanarMotionModel>(W(0), W(1), Pose2(0, 0, 0),
 | 
			
		||||
  auto still = std::make_shared<PlanarMotionModel>(W(0), W(1), Pose2(0, 0, 0),
 | 
			
		||||
                                                     noise_model),
 | 
			
		||||
       moving = boost::make_shared<PlanarMotionModel>(W(0), W(1), odometry,
 | 
			
		||||
       moving = std::make_shared<PlanarMotionModel>(W(0), W(1), odometry,
 | 
			
		||||
                                                      noise_model);
 | 
			
		||||
  std::vector<PlanarMotionModel::shared_ptr> components = {moving, still};
 | 
			
		||||
  auto mixtureFactor = boost::make_shared<MixtureFactor>(
 | 
			
		||||
  auto mixtureFactor = std::make_shared<MixtureFactor>(
 | 
			
		||||
      contKeys, DiscreteKeys{gtsam::DiscreteKey(M(1), 2)}, components);
 | 
			
		||||
  fg.push_back(mixtureFactor);
 | 
			
		||||
 | 
			
		||||
| 
						 | 
				
			
			@ -481,12 +481,12 @@ TEST(HybridNonlinearISAM, NonTrivial) {
 | 
			
		|||
  /*************** Run Round 3 ***************/
 | 
			
		||||
  // Add odometry factor with discrete modes.
 | 
			
		||||
  contKeys = {W(1), W(2)};
 | 
			
		||||
  still = boost::make_shared<PlanarMotionModel>(W(1), W(2), Pose2(0, 0, 0),
 | 
			
		||||
  still = std::make_shared<PlanarMotionModel>(W(1), W(2), Pose2(0, 0, 0),
 | 
			
		||||
                                                noise_model);
 | 
			
		||||
  moving =
 | 
			
		||||
      boost::make_shared<PlanarMotionModel>(W(1), W(2), odometry, noise_model);
 | 
			
		||||
      std::make_shared<PlanarMotionModel>(W(1), W(2), odometry, noise_model);
 | 
			
		||||
  components = {moving, still};
 | 
			
		||||
  mixtureFactor = boost::make_shared<MixtureFactor>(
 | 
			
		||||
  mixtureFactor = std::make_shared<MixtureFactor>(
 | 
			
		||||
      contKeys, DiscreteKeys{gtsam::DiscreteKey(M(2), 2)}, components);
 | 
			
		||||
  fg.push_back(mixtureFactor);
 | 
			
		||||
 | 
			
		||||
| 
						 | 
				
			
			@ -524,12 +524,12 @@ TEST(HybridNonlinearISAM, NonTrivial) {
 | 
			
		|||
  /*************** Run Round 4 ***************/
 | 
			
		||||
  // Add odometry factor with discrete modes.
 | 
			
		||||
  contKeys = {W(2), W(3)};
 | 
			
		||||
  still = boost::make_shared<PlanarMotionModel>(W(2), W(3), Pose2(0, 0, 0),
 | 
			
		||||
  still = std::make_shared<PlanarMotionModel>(W(2), W(3), Pose2(0, 0, 0),
 | 
			
		||||
                                                noise_model);
 | 
			
		||||
  moving =
 | 
			
		||||
      boost::make_shared<PlanarMotionModel>(W(2), W(3), odometry, noise_model);
 | 
			
		||||
      std::make_shared<PlanarMotionModel>(W(2), W(3), odometry, noise_model);
 | 
			
		||||
  components = {moving, still};
 | 
			
		||||
  mixtureFactor = boost::make_shared<MixtureFactor>(
 | 
			
		||||
  mixtureFactor = std::make_shared<MixtureFactor>(
 | 
			
		||||
      contKeys, DiscreteKeys{gtsam::DiscreteKey(M(3), 2)}, components);
 | 
			
		||||
  fg.push_back(mixtureFactor);
 | 
			
		||||
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -52,9 +52,9 @@ TEST(MixtureFactor, Printing) {
 | 
			
		|||
  auto model = noiseModel::Diagonal::Sigmas(sigmas, false);
 | 
			
		||||
 | 
			
		||||
  auto f0 =
 | 
			
		||||
      boost::make_shared<BetweenFactor<double>>(X(1), X(2), between0, model);
 | 
			
		||||
      std::make_shared<BetweenFactor<double>>(X(1), X(2), between0, model);
 | 
			
		||||
  auto f1 =
 | 
			
		||||
      boost::make_shared<BetweenFactor<double>>(X(1), X(2), between1, model);
 | 
			
		||||
      std::make_shared<BetweenFactor<double>>(X(1), X(2), between1, model);
 | 
			
		||||
  std::vector<NonlinearFactor::shared_ptr> factors{f0, f1};
 | 
			
		||||
 | 
			
		||||
  MixtureFactor mixtureFactor({X(1), X(2)}, {m1}, factors);
 | 
			
		||||
| 
						 | 
				
			
			@ -80,9 +80,9 @@ static MixtureFactor getMixtureFactor() {
 | 
			
		|||
  auto model = noiseModel::Diagonal::Sigmas(sigmas, false);
 | 
			
		||||
 | 
			
		||||
  auto f0 =
 | 
			
		||||
      boost::make_shared<BetweenFactor<double>>(X(1), X(2), between0, model);
 | 
			
		||||
      std::make_shared<BetweenFactor<double>>(X(1), X(2), between0, model);
 | 
			
		||||
  auto f1 =
 | 
			
		||||
      boost::make_shared<BetweenFactor<double>>(X(1), X(2), between1, model);
 | 
			
		||||
      std::make_shared<BetweenFactor<double>>(X(1), X(2), between1, model);
 | 
			
		||||
  std::vector<NonlinearFactor::shared_ptr> factors{f0, f1};
 | 
			
		||||
 | 
			
		||||
  return MixtureFactor({X(1), X(2)}, {m1}, factors);
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -80,8 +80,8 @@ TEST(HybridSerialization, GaussianMixtureFactor) {
 | 
			
		|||
  auto A = Matrix::Zero(2, 1);
 | 
			
		||||
  auto b0 = Matrix::Zero(2, 1);
 | 
			
		||||
  auto b1 = Matrix::Ones(2, 1);
 | 
			
		||||
  auto f0 = boost::make_shared<JacobianFactor>(X(0), A, b0);
 | 
			
		||||
  auto f1 = boost::make_shared<JacobianFactor>(X(0), A, b1);
 | 
			
		||||
  auto f0 = std::make_shared<JacobianFactor>(X(0), A, b0);
 | 
			
		||||
  auto f1 = std::make_shared<JacobianFactor>(X(0), A, b1);
 | 
			
		||||
  std::vector<GaussianFactor::shared_ptr> factors{f0, f1};
 | 
			
		||||
 | 
			
		||||
  const GaussianMixtureFactor factor(continuousKeys, discreteKeys, factors);
 | 
			
		||||
| 
						 | 
				
			
			@ -96,7 +96,7 @@ TEST(HybridSerialization, GaussianMixtureFactor) {
 | 
			
		|||
TEST(HybridSerialization, HybridConditional) {
 | 
			
		||||
  const DiscreteKey mode(M(0), 2);
 | 
			
		||||
  Matrix1 I = Matrix1::Identity();
 | 
			
		||||
  const auto conditional = boost::make_shared<GaussianConditional>(
 | 
			
		||||
  const auto conditional = std::make_shared<GaussianConditional>(
 | 
			
		||||
      GaussianConditional::FromMeanAndStddev(Z(0), I, X(0), Vector1(0), 0.5));
 | 
			
		||||
  const HybridConditional hc(conditional);
 | 
			
		||||
 | 
			
		||||
| 
						 | 
				
			
			@ -110,9 +110,9 @@ TEST(HybridSerialization, HybridConditional) {
 | 
			
		|||
TEST(HybridSerialization, GaussianMixture) {
 | 
			
		||||
  const DiscreteKey mode(M(0), 2);
 | 
			
		||||
  Matrix1 I = Matrix1::Identity();
 | 
			
		||||
  const auto conditional0 = boost::make_shared<GaussianConditional>(
 | 
			
		||||
  const auto conditional0 = std::make_shared<GaussianConditional>(
 | 
			
		||||
      GaussianConditional::FromMeanAndStddev(Z(0), I, X(0), Vector1(0), 0.5));
 | 
			
		||||
  const auto conditional1 = boost::make_shared<GaussianConditional>(
 | 
			
		||||
  const auto conditional1 = std::make_shared<GaussianConditional>(
 | 
			
		||||
      GaussianConditional::FromMeanAndStddev(Z(0), I, X(0), Vector1(0), 3));
 | 
			
		||||
  const GaussianMixture gm({Z(0)}, {X(0)}, {mode},
 | 
			
		||||
                           {conditional0, conditional1});
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -20,7 +20,7 @@
 | 
			
		|||
 | 
			
		||||
#include <gtsam/inference/FactorGraph.h>
 | 
			
		||||
 | 
			
		||||
#include <boost/shared_ptr.hpp>
 | 
			
		||||
#include <memory>
 | 
			
		||||
#include <string>
 | 
			
		||||
 | 
			
		||||
namespace gtsam {
 | 
			
		||||
| 
						 | 
				
			
			@ -37,7 +37,7 @@ class BayesNet : public FactorGraph<CONDITIONAL> {
 | 
			
		|||
  typedef FactorGraph<CONDITIONAL> Base;
 | 
			
		||||
 | 
			
		||||
 public:
 | 
			
		||||
  typedef typename boost::shared_ptr<CONDITIONAL>
 | 
			
		||||
  typedef typename std::shared_ptr<CONDITIONAL>
 | 
			
		||||
      sharedConditional;  ///< A shared pointer to a conditional
 | 
			
		||||
 | 
			
		||||
 protected:
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -155,7 +155,7 @@ namespace gtsam {
 | 
			
		|||
  struct _pushCliqueFunctor {
 | 
			
		||||
    _pushCliqueFunctor(FactorGraph<FACTOR>* graph_) : graph(graph_) {}
 | 
			
		||||
    FactorGraph<FACTOR>* graph;
 | 
			
		||||
    int operator()(const boost::shared_ptr<CLIQUE>& clique, int dummy) {
 | 
			
		||||
    int operator()(const std::shared_ptr<CLIQUE>& clique, int dummy) {
 | 
			
		||||
      graph->push_back(clique->conditional_);
 | 
			
		||||
      return 0;
 | 
			
		||||
    }
 | 
			
		||||
| 
						 | 
				
			
			@ -181,11 +181,11 @@ namespace gtsam {
 | 
			
		|||
  /* ************************************************************************* */
 | 
			
		||||
  namespace {
 | 
			
		||||
    template<typename NODE>
 | 
			
		||||
    boost::shared_ptr<NODE>
 | 
			
		||||
      BayesTreeCloneForestVisitorPre(const boost::shared_ptr<NODE>& node, const boost::shared_ptr<NODE>& parentPointer)
 | 
			
		||||
    std::shared_ptr<NODE>
 | 
			
		||||
      BayesTreeCloneForestVisitorPre(const std::shared_ptr<NODE>& node, const std::shared_ptr<NODE>& parentPointer)
 | 
			
		||||
    {
 | 
			
		||||
      // Clone the current node and add it to its cloned parent
 | 
			
		||||
      boost::shared_ptr<NODE> clone = boost::make_shared<NODE>(*node);
 | 
			
		||||
      std::shared_ptr<NODE> clone = std::make_shared<NODE>(*node);
 | 
			
		||||
      clone->children.clear();
 | 
			
		||||
      clone->parent_ = parentPointer;
 | 
			
		||||
      parentPointer->children.push_back(clone);
 | 
			
		||||
| 
						 | 
				
			
			@ -197,7 +197,7 @@ namespace gtsam {
 | 
			
		|||
  template<class CLIQUE>
 | 
			
		||||
  BayesTree<CLIQUE>& BayesTree<CLIQUE>::operator=(const This& other) {
 | 
			
		||||
    this->clear();
 | 
			
		||||
    boost::shared_ptr<Clique> rootContainer = boost::make_shared<Clique>();
 | 
			
		||||
    std::shared_ptr<Clique> rootContainer = std::make_shared<Clique>();
 | 
			
		||||
    treeTraversal::DepthFirstForest(other, rootContainer, BayesTreeCloneForestVisitorPre<Clique>);
 | 
			
		||||
    for(const sharedClique& root: rootContainer->children) {
 | 
			
		||||
      root->parent_ = typename Clique::weak_ptr(); // Reset the parent since it's set to the dummy clique
 | 
			
		||||
| 
						 | 
				
			
			@ -292,7 +292,7 @@ namespace gtsam {
 | 
			
		|||
    BayesTree<CLIQUE>::joint(Key j1, Key j2, const Eliminate& function) const
 | 
			
		||||
  {
 | 
			
		||||
    gttic(BayesTree_joint);
 | 
			
		||||
    return boost::make_shared<FactorGraphType>(*jointBayesNet(j1, j2, function));
 | 
			
		||||
    return std::make_shared<FactorGraphType>(*jointBayesNet(j1, j2, function));
 | 
			
		||||
  }
 | 
			
		||||
 | 
			
		||||
  /* ************************************************************************* */
 | 
			
		||||
| 
						 | 
				
			
			@ -352,7 +352,7 @@ namespace gtsam {
 | 
			
		|||
      // Factor the shortcuts to be conditioned on the full root
 | 
			
		||||
      // Get the set of variables to eliminate, which is C1\B.
 | 
			
		||||
      gttic(Full_root_factoring);
 | 
			
		||||
      boost::shared_ptr<typename EliminationTraitsType::BayesTreeType> p_C1_B; {
 | 
			
		||||
      std::shared_ptr<typename EliminationTraitsType::BayesTreeType> p_C1_B; {
 | 
			
		||||
        KeyVector C1_minus_B; {
 | 
			
		||||
          KeySet C1_minus_B_set(C1->conditional()->beginParents(), C1->conditional()->endParents());
 | 
			
		||||
          for(const Key j: *B->conditional()) {
 | 
			
		||||
| 
						 | 
				
			
			@ -364,7 +364,7 @@ namespace gtsam {
 | 
			
		|||
        boost::tie(p_C1_B, temp_remaining) =
 | 
			
		||||
          FactorGraphType(p_C1_Bred).eliminatePartialMultifrontal(Ordering(C1_minus_B), function);
 | 
			
		||||
      }
 | 
			
		||||
      boost::shared_ptr<typename EliminationTraitsType::BayesTreeType> p_C2_B; {
 | 
			
		||||
      std::shared_ptr<typename EliminationTraitsType::BayesTreeType> p_C2_B; {
 | 
			
		||||
        KeyVector C2_minus_B; {
 | 
			
		||||
          KeySet C2_minus_B_set(C2->conditional()->beginParents(), C2->conditional()->endParents());
 | 
			
		||||
          for(const Key j: *B->conditional()) {
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
Some files were not shown because too many files have changed in this diff Show More
		Loading…
	
		Reference in New Issue