shared_ptr, make_shared, allocate_shared
parent
173fb76367
commit
852e8768c0
|
@ -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
|
||||
|
||||
|
|
|
@ -70,7 +70,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):
|
||||
|
|
|
@ -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,8 +65,8 @@ 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 =
|
||||
for(const std::shared_ptr<NonlinearFactor>& factor: *graph) {
|
||||
std::shared_ptr<BetweenFactor<Pose3> > pose3Between =
|
||||
boost::dynamic_pointer_cast<BetweenFactor<Pose3> >(factor);
|
||||
if (pose3Between){
|
||||
Key key1, key2;
|
||||
|
|
|
@ -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);
|
||||
|
|
|
@ -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
|
||||
|
|
|
@ -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;
|
||||
|
|
|
@ -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)
|
||||
|
||||
|
|
|
@ -114,8 +114,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
|
||||
|
|
|
@ -45,7 +45,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;
|
||||
|
|
|
@ -34,7 +34,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 +46,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)...);
|
||||
}
|
||||
|
||||
}
|
||||
|
|
|
@ -85,7 +85,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,13 @@
|
|||
|
||||
#include <vector>
|
||||
#include <list>
|
||||
#include <boost/shared_ptr.hpp>
|
||||
#include <memory>
|
||||
#include <boost/make_shared.hpp>
|
||||
|
||||
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 +48,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(
|
||||
|
|
|
@ -157,8 +157,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 +184,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 +216,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 +260,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,7 +27,7 @@
|
|||
#include <stack>
|
||||
#include <vector>
|
||||
#include <string>
|
||||
#include <boost/shared_ptr.hpp>
|
||||
#include <memory>
|
||||
#include <boost/make_shared.hpp>
|
||||
|
||||
namespace gtsam {
|
||||
|
@ -41,10 +41,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 +52,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 +78,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 +169,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 +204,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,7 +18,7 @@
|
|||
|
||||
#include <gtsam/global_includes.h>
|
||||
|
||||
#include <boost/shared_ptr.hpp>
|
||||
#include <memory>
|
||||
#include <boost/make_shared.hpp>
|
||||
|
||||
#ifdef GTSAM_USE_TBB
|
||||
|
@ -37,8 +37,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 +48,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 +77,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 +107,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 +140,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
|
||||
|
|
|
@ -183,7 +183,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.
|
||||
|
@ -387,14 +387,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 +409,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 +417,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 +435,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 +476,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 +489,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,7 +568,7 @@ namespace gtsam {
|
|||
for (Iterator it = begin; it != end; it++) {
|
||||
if (it->root_->isLeaf())
|
||||
continue;
|
||||
boost::shared_ptr<const Choice> c =
|
||||
std::shared_ptr<const Choice> c =
|
||||
boost::dynamic_pointer_cast<const Choice>(it->root_);
|
||||
if (!highestLabel || c->label() > *highestLabel) {
|
||||
highestLabel = c->label();
|
||||
|
@ -578,14 +578,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 +647,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);
|
||||
|
|
|
@ -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;
|
||||
|
|
|
@ -127,7 +127,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 +160,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:
|
||||
|
|
|
@ -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
|
||||
/// @{
|
||||
|
|
|
@ -195,7 +195,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 +220,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);
|
||||
}
|
||||
|
||||
/* ****************************************************************************/
|
||||
|
|
|
@ -23,7 +23,7 @@
|
|||
#include <gtsam/discrete/Signature.h>
|
||||
|
||||
#include <boost/make_shared.hpp>
|
||||
#include <boost/shared_ptr.hpp>
|
||||
#include <memory>
|
||||
#include <string>
|
||||
#include <vector>
|
||||
|
||||
|
@ -41,7 +41,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
|
||||
|
|
|
@ -136,7 +136,7 @@ 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);
|
||||
|
||||
|
@ -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);
|
||||
|
|
|
@ -48,7 +48,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 +62,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 +89,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.
|
||||
|
|
|
@ -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
|
||||
/// @{
|
||||
|
|
|
@ -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),
|
||||
|
|
|
@ -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
|
||||
|
||||
|
|
|
@ -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
|
||||
/// @{
|
||||
|
|
|
@ -245,7 +245,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 +266,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 +281,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 +301,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 +362,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,
|
||||
|
|
|
@ -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(
|
||||
|
@ -213,7 +213,7 @@ boost::shared_ptr<GaussianMixtureFactor> GaussianMixture::likelihood(
|
|||
return boost::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);
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
|
@ -162,9 +162,9 @@ void HybridBayesNet::updateDiscreteConditionals(
|
|||
// 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()),
|
||||
|
|
|
@ -26,7 +26,7 @@
|
|||
#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 +63,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 +111,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 +120,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 +128,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
|
||||
|
@ -174,7 +174,7 @@ class GTSAM_EXPORT HybridConditional
|
|||
}
|
||||
|
||||
/// 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
|
||||
|
||||
|
|
|
@ -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
|
||||
|
|
|
@ -62,7 +62,7 @@ using boost::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,14 +50,14 @@ 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
|
||||
|
@ -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
|
||||
|
|
|
@ -46,7 +46,7 @@ HybridGaussianFactorGraph::shared_ptr HybridNonlinearFactorGraph::linearize(
|
|||
using boost::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
|
||||
|
|
|
@ -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;
|
||||
|
@ -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);
|
||||
}
|
||||
|
||||
|
|
|
@ -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));
|
||||
}
|
||||
|
||||
/**
|
||||
|
@ -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};
|
||||
}
|
||||
|
||||
|
|
|
@ -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*/,
|
||||
|
@ -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));
|
||||
|
||||
|
@ -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()) {
|
||||
|
|
|
@ -19,7 +19,7 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#include <boost/shared_ptr.hpp>
|
||||
#include <memory>
|
||||
|
||||
#include <gtsam/inference/Key.h>
|
||||
#include <gtsam/base/FastList.h>
|
||||
|
@ -67,21 +67,21 @@ namespace gtsam {
|
|||
{
|
||||
protected:
|
||||
typedef BayesTree<CLIQUE> This;
|
||||
typedef boost::shared_ptr<This> shared_ptr;
|
||||
typedef std::shared_ptr<This> shared_ptr;
|
||||
|
||||
public:
|
||||
typedef CLIQUE Clique; ///< The clique type, normally BayesTreeClique
|
||||
typedef boost::shared_ptr<Clique> sharedClique; ///< Shared pointer to a clique
|
||||
typedef std::shared_ptr<Clique> sharedClique; ///< Shared pointer to a clique
|
||||
typedef Clique Node; ///< Synonym for Clique (TODO: remove)
|
||||
typedef sharedClique sharedNode; ///< Synonym for sharedClique (TODO: remove)
|
||||
typedef typename CLIQUE::ConditionalType ConditionalType;
|
||||
typedef boost::shared_ptr<ConditionalType> sharedConditional;
|
||||
typedef std::shared_ptr<ConditionalType> sharedConditional;
|
||||
typedef typename CLIQUE::BayesNetType BayesNetType;
|
||||
typedef boost::shared_ptr<BayesNetType> sharedBayesNet;
|
||||
typedef std::shared_ptr<BayesNetType> sharedBayesNet;
|
||||
typedef typename CLIQUE::FactorType FactorType;
|
||||
typedef boost::shared_ptr<FactorType> sharedFactor;
|
||||
typedef std::shared_ptr<FactorType> sharedFactor;
|
||||
typedef typename CLIQUE::FactorGraphType FactorGraphType;
|
||||
typedef boost::shared_ptr<FactorGraphType> sharedFactorGraph;
|
||||
typedef std::shared_ptr<FactorGraphType> sharedFactorGraph;
|
||||
typedef typename FactorGraphType::Eliminate Eliminate;
|
||||
typedef typename CLIQUE::EliminationTraitsType EliminationTraitsType;
|
||||
|
||||
|
@ -278,7 +278,7 @@ namespace gtsam {
|
|||
typedef CLIQUE CliqueType;
|
||||
typedef typename CLIQUE::ConditionalType Base;
|
||||
|
||||
boost::shared_ptr<CliqueType> clique;
|
||||
std::shared_ptr<CliqueType> clique;
|
||||
|
||||
/**
|
||||
* @brief Construct a new Bayes Tree Orphan Wrapper object
|
||||
|
@ -290,7 +290,7 @@ namespace gtsam {
|
|||
* @param clique Orphan clique to add for further consideration in
|
||||
* elimination.
|
||||
*/
|
||||
BayesTreeOrphanWrapper(const boost::shared_ptr<CliqueType>& clique)
|
||||
BayesTreeOrphanWrapper(const std::shared_ptr<CliqueType>& clique)
|
||||
: clique(clique) {
|
||||
this->keys_.assign(clique->conditional()->beginParents(),
|
||||
clique->conditional()->endParents());
|
||||
|
|
|
@ -129,7 +129,7 @@ namespace gtsam {
|
|||
KeyVector keep = shortcut_indices(B, p_Cp_B);
|
||||
|
||||
// Marginalize out everything except S union B
|
||||
boost::shared_ptr<FactorGraphType> p_S_B = p_Cp_B.marginal(keep, function);
|
||||
std::shared_ptr<FactorGraphType> p_S_B = p_Cp_B.marginal(keep, function);
|
||||
return *p_S_B->eliminatePartialSequential(S_setminus_B, function).first;
|
||||
}
|
||||
else
|
||||
|
@ -198,7 +198,7 @@ namespace gtsam {
|
|||
// initialize with separator marginal P(S)
|
||||
FactorGraphType p_C = this->separatorMarginal(function);
|
||||
// add the conditional P(F|S)
|
||||
p_C += boost::shared_ptr<FactorType>(this->conditional_);
|
||||
p_C += std::shared_ptr<FactorType>(this->conditional_);
|
||||
return p_C;
|
||||
}
|
||||
|
||||
|
|
|
@ -52,16 +52,16 @@ namespace gtsam {
|
|||
typedef BayesTreeCliqueBase<DERIVED, FACTORGRAPH> This;
|
||||
typedef DERIVED DerivedType;
|
||||
typedef EliminationTraits<FACTORGRAPH> EliminationTraitsType;
|
||||
typedef boost::shared_ptr<This> shared_ptr;
|
||||
typedef boost::weak_ptr<This> weak_ptr;
|
||||
typedef boost::shared_ptr<DerivedType> derived_ptr;
|
||||
typedef boost::weak_ptr<DerivedType> derived_weak_ptr;
|
||||
typedef std::shared_ptr<This> shared_ptr;
|
||||
typedef std::weak_ptr<This> weak_ptr;
|
||||
typedef std::shared_ptr<DerivedType> derived_ptr;
|
||||
typedef std::weak_ptr<DerivedType> derived_weak_ptr;
|
||||
|
||||
public:
|
||||
typedef FACTORGRAPH FactorGraphType;
|
||||
typedef typename EliminationTraitsType::BayesNetType BayesNetType;
|
||||
typedef typename BayesNetType::ConditionalType ConditionalType;
|
||||
typedef boost::shared_ptr<ConditionalType> sharedConditional;
|
||||
typedef std::shared_ptr<ConditionalType> sharedConditional;
|
||||
typedef typename FactorGraphType::FactorType FactorType;
|
||||
typedef typename FactorGraphType::Eliminate Eliminate;
|
||||
|
||||
|
|
|
@ -41,7 +41,7 @@ std::vector<size_t> ClusterTree<GRAPH>::Cluster::nrFrontalsOfChildren() const {
|
|||
|
||||
/* ************************************************************************* */
|
||||
template <class GRAPH>
|
||||
void ClusterTree<GRAPH>::Cluster::merge(const boost::shared_ptr<Cluster>& cluster) {
|
||||
void ClusterTree<GRAPH>::Cluster::merge(const std::shared_ptr<Cluster>& cluster) {
|
||||
// Merge keys. For efficiency, we add keys in reverse order at end, calling reverse after..
|
||||
orderedFrontalKeys.insert(orderedFrontalKeys.end(), cluster->orderedFrontalKeys.rbegin(),
|
||||
cluster->orderedFrontalKeys.rend());
|
||||
|
@ -123,15 +123,15 @@ struct EliminationData {
|
|||
EliminationData* const parentData;
|
||||
size_t myIndexInParent;
|
||||
FastVector<sharedFactor> childFactors;
|
||||
boost::shared_ptr<BTNode> bayesTreeNode;
|
||||
std::shared_ptr<BTNode> bayesTreeNode;
|
||||
#ifdef GTSAM_USE_TBB
|
||||
boost::shared_ptr<std::mutex> writeLock;
|
||||
std::shared_ptr<std::mutex> writeLock;
|
||||
#endif
|
||||
|
||||
EliminationData(EliminationData* _parentData, size_t nChildren) :
|
||||
parentData(_parentData), bayesTreeNode(boost::make_shared<BTNode>())
|
||||
parentData(_parentData), bayesTreeNode(std::make_shared<BTNode>())
|
||||
#ifdef GTSAM_USE_TBB
|
||||
, writeLock(boost::make_shared<std::mutex>())
|
||||
, writeLock(std::make_shared<std::mutex>())
|
||||
#endif
|
||||
{
|
||||
if (parentData) {
|
||||
|
@ -241,13 +241,13 @@ EliminatableClusterTree<BAYESTREE, GRAPH>& EliminatableClusterTree<BAYESTREE, GR
|
|||
|
||||
/* ************************************************************************* */
|
||||
template <class BAYESTREE, class GRAPH>
|
||||
std::pair<boost::shared_ptr<BAYESTREE>, boost::shared_ptr<GRAPH> >
|
||||
std::pair<std::shared_ptr<BAYESTREE>, std::shared_ptr<GRAPH> >
|
||||
EliminatableClusterTree<BAYESTREE, GRAPH>::eliminate(const Eliminate& function) const {
|
||||
gttic(ClusterTree_eliminate);
|
||||
// Do elimination (depth-first traversal). The rootsContainer stores a 'dummy' BayesTree node
|
||||
// that contains all of the roots as its children. rootsContainer also stores the remaining
|
||||
// un-eliminated factors passed up from the roots.
|
||||
boost::shared_ptr<BayesTreeType> result = boost::make_shared<BayesTreeType>();
|
||||
std::shared_ptr<BayesTreeType> result = std::make_shared<BayesTreeType>();
|
||||
|
||||
typedef EliminationData<This> Data;
|
||||
Data rootsContainer(0, this->nrRoots());
|
||||
|
@ -264,7 +264,7 @@ EliminatableClusterTree<BAYESTREE, GRAPH>::eliminate(const Eliminate& function)
|
|||
rootsContainer.bayesTreeNode->children.end());
|
||||
|
||||
// Add remaining factors that were not involved with eliminated variables
|
||||
boost::shared_ptr<FactorGraphType> remaining = boost::make_shared<FactorGraphType>();
|
||||
std::shared_ptr<FactorGraphType> remaining = std::make_shared<FactorGraphType>();
|
||||
remaining->reserve(remainingFactors_.size() + rootsContainer.childFactors.size());
|
||||
remaining->push_back(remainingFactors_.begin(), remainingFactors_.end());
|
||||
for (const sharedFactor& factor : rootsContainer.childFactors) {
|
||||
|
|
|
@ -26,15 +26,15 @@ class ClusterTree {
|
|||
public:
|
||||
typedef GRAPH FactorGraphType; ///< The factor graph type
|
||||
typedef ClusterTree<GRAPH> 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
|
||||
|
||||
typedef typename GRAPH::FactorType FactorType; ///< The type of factors
|
||||
typedef boost::shared_ptr<FactorType> sharedFactor; ///< Shared pointer to a factor
|
||||
typedef std::shared_ptr<FactorType> sharedFactor; ///< Shared pointer to a factor
|
||||
|
||||
/// A Cluster is just a collection of factors
|
||||
// TODO(frank): re-factor JunctionTree so we can make members private
|
||||
struct Cluster {
|
||||
typedef FastVector<boost::shared_ptr<Cluster> > Children;
|
||||
typedef FastVector<std::shared_ptr<Cluster> > Children;
|
||||
Children children; ///< sub-trees
|
||||
|
||||
typedef Ordering Keys;
|
||||
|
@ -68,7 +68,7 @@ class ClusterTree {
|
|||
}
|
||||
|
||||
/// Add a child cluster
|
||||
void addChild(const boost::shared_ptr<Cluster>& cluster) {
|
||||
void addChild(const std::shared_ptr<Cluster>& cluster) {
|
||||
children.push_back(cluster);
|
||||
problemSize_ = std::max(problemSize_, cluster->problemSize_);
|
||||
}
|
||||
|
@ -97,13 +97,13 @@ class ClusterTree {
|
|||
std::vector<size_t> nrFrontalsOfChildren() const;
|
||||
|
||||
/// Merge in given cluster
|
||||
void merge(const boost::shared_ptr<Cluster>& cluster);
|
||||
void merge(const std::shared_ptr<Cluster>& cluster);
|
||||
|
||||
/// Merge all children for which bit is set into this node
|
||||
void mergeChildren(const std::vector<bool>& merge);
|
||||
};
|
||||
|
||||
typedef boost::shared_ptr<Cluster> sharedCluster; ///< Shared pointer to Cluster
|
||||
typedef std::shared_ptr<Cluster> sharedCluster; ///< Shared pointer to Cluster
|
||||
|
||||
// Define Node=Cluster for compatibility with tree traversal functions
|
||||
typedef Cluster Node;
|
||||
|
@ -142,11 +142,11 @@ class ClusterTree {
|
|||
/// @name Advanced Interface
|
||||
/// @{
|
||||
|
||||
void addRoot(const boost::shared_ptr<Cluster>& cluster) {
|
||||
void addRoot(const std::shared_ptr<Cluster>& cluster) {
|
||||
roots_.push_back(cluster);
|
||||
}
|
||||
|
||||
void addChildrenAsRoots(const boost::shared_ptr<Cluster>& cluster) {
|
||||
void addChildrenAsRoots(const std::shared_ptr<Cluster>& cluster) {
|
||||
for (auto child : cluster->children)
|
||||
this->addRoot(child);
|
||||
}
|
||||
|
@ -186,15 +186,15 @@ class EliminatableClusterTree : public ClusterTree<GRAPH> {
|
|||
typedef BAYESTREE BayesTreeType; ///< The BayesTree type produced by elimination
|
||||
typedef GRAPH FactorGraphType; ///< The factor graph type
|
||||
typedef EliminatableClusterTree<BAYESTREE, GRAPH> 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
|
||||
|
||||
typedef typename BAYESTREE::ConditionalType ConditionalType; ///< The type of conditionals
|
||||
typedef boost::shared_ptr<ConditionalType>
|
||||
typedef std::shared_ptr<ConditionalType>
|
||||
sharedConditional; ///< Shared pointer to a conditional
|
||||
|
||||
typedef typename GRAPH::Eliminate Eliminate; ///< Typedef for an eliminate subroutine
|
||||
typedef typename GRAPH::FactorType FactorType; ///< The type of factors
|
||||
typedef boost::shared_ptr<FactorType> sharedFactor; ///< Shared pointer to a factor
|
||||
typedef std::shared_ptr<FactorType> sharedFactor; ///< Shared pointer to a factor
|
||||
|
||||
protected:
|
||||
FastVector<sharedFactor> remainingFactors_;
|
||||
|
@ -219,7 +219,7 @@ class EliminatableClusterTree : public ClusterTree<GRAPH> {
|
|||
* in GaussianFactorGraph.h
|
||||
* @return The Bayes tree and factor graph resulting from elimination
|
||||
*/
|
||||
std::pair<boost::shared_ptr<BayesTreeType>, boost::shared_ptr<FactorGraphType> > eliminate(
|
||||
std::pair<std::shared_ptr<BayesTreeType>, std::shared_ptr<FactorGraphType> > eliminate(
|
||||
const Eliminate& function) const;
|
||||
|
||||
/// @}
|
||||
|
|
|
@ -26,7 +26,7 @@ namespace gtsam {
|
|||
|
||||
/* ************************************************************************* */
|
||||
template<class FACTORGRAPH>
|
||||
boost::shared_ptr<typename EliminateableFactorGraph<FACTORGRAPH>::BayesNetType>
|
||||
std::shared_ptr<typename EliminateableFactorGraph<FACTORGRAPH>::BayesNetType>
|
||||
EliminateableFactorGraph<FACTORGRAPH>::eliminateSequential(
|
||||
OptionalOrderingType orderingType, const Eliminate& function,
|
||||
OptionalVariableIndex variableIndex) const {
|
||||
|
@ -60,7 +60,7 @@ namespace gtsam {
|
|||
|
||||
/* ************************************************************************* */
|
||||
template<class FACTORGRAPH>
|
||||
boost::shared_ptr<typename EliminateableFactorGraph<FACTORGRAPH>::BayesNetType>
|
||||
std::shared_ptr<typename EliminateableFactorGraph<FACTORGRAPH>::BayesNetType>
|
||||
EliminateableFactorGraph<FACTORGRAPH>::eliminateSequential(
|
||||
const Ordering& ordering, const Eliminate& function,
|
||||
OptionalVariableIndex variableIndex) const
|
||||
|
@ -73,8 +73,8 @@ namespace gtsam {
|
|||
gttic(eliminateSequential);
|
||||
// Do elimination
|
||||
EliminationTreeType etree(asDerived(), (*variableIndex).get(), ordering);
|
||||
boost::shared_ptr<BayesNetType> bayesNet;
|
||||
boost::shared_ptr<FactorGraphType> factorGraph;
|
||||
std::shared_ptr<BayesNetType> bayesNet;
|
||||
std::shared_ptr<FactorGraphType> factorGraph;
|
||||
boost::tie(bayesNet,factorGraph) = etree.eliminate(function);
|
||||
// If any factors are remaining, the ordering was incomplete
|
||||
if(!factorGraph->empty())
|
||||
|
@ -86,7 +86,7 @@ namespace gtsam {
|
|||
|
||||
/* ************************************************************************* */
|
||||
template <class FACTORGRAPH>
|
||||
boost::shared_ptr<
|
||||
std::shared_ptr<
|
||||
typename EliminateableFactorGraph<FACTORGRAPH>::BayesTreeType>
|
||||
EliminateableFactorGraph<FACTORGRAPH>::eliminateMultifrontal(
|
||||
OptionalOrderingType orderingType, const Eliminate& function,
|
||||
|
@ -123,7 +123,7 @@ namespace gtsam {
|
|||
|
||||
/* ************************************************************************* */
|
||||
template<class FACTORGRAPH>
|
||||
boost::shared_ptr<typename EliminateableFactorGraph<FACTORGRAPH>::BayesTreeType>
|
||||
std::shared_ptr<typename EliminateableFactorGraph<FACTORGRAPH>::BayesTreeType>
|
||||
EliminateableFactorGraph<FACTORGRAPH>::eliminateMultifrontal(
|
||||
const Ordering& ordering, const Eliminate& function,
|
||||
OptionalVariableIndex variableIndex) const
|
||||
|
@ -137,8 +137,8 @@ namespace gtsam {
|
|||
// Do elimination with given ordering
|
||||
EliminationTreeType etree(asDerived(), (*variableIndex).get(), ordering);
|
||||
JunctionTreeType junctionTree(etree);
|
||||
boost::shared_ptr<BayesTreeType> bayesTree;
|
||||
boost::shared_ptr<FactorGraphType> factorGraph;
|
||||
std::shared_ptr<BayesTreeType> bayesTree;
|
||||
std::shared_ptr<FactorGraphType> factorGraph;
|
||||
boost::tie(bayesTree,factorGraph) = junctionTree.eliminate(function);
|
||||
// If any factors are remaining, the ordering was incomplete
|
||||
if(!factorGraph->empty())
|
||||
|
@ -150,7 +150,7 @@ namespace gtsam {
|
|||
|
||||
/* ************************************************************************* */
|
||||
template<class FACTORGRAPH>
|
||||
std::pair<boost::shared_ptr<typename EliminateableFactorGraph<FACTORGRAPH>::BayesNetType>, boost::shared_ptr<FACTORGRAPH> >
|
||||
std::pair<std::shared_ptr<typename EliminateableFactorGraph<FACTORGRAPH>::BayesNetType>, std::shared_ptr<FACTORGRAPH> >
|
||||
EliminateableFactorGraph<FACTORGRAPH>::eliminatePartialSequential(
|
||||
const Ordering& ordering, const Eliminate& function, OptionalVariableIndex variableIndex) const
|
||||
{
|
||||
|
@ -168,7 +168,7 @@ namespace gtsam {
|
|||
|
||||
/* ************************************************************************* */
|
||||
template<class FACTORGRAPH>
|
||||
std::pair<boost::shared_ptr<typename EliminateableFactorGraph<FACTORGRAPH>::BayesNetType>, boost::shared_ptr<FACTORGRAPH> >
|
||||
std::pair<std::shared_ptr<typename EliminateableFactorGraph<FACTORGRAPH>::BayesNetType>, std::shared_ptr<FACTORGRAPH> >
|
||||
EliminateableFactorGraph<FACTORGRAPH>::eliminatePartialSequential(
|
||||
const KeyVector& variables, const Eliminate& function, OptionalVariableIndex variableIndex) const
|
||||
{
|
||||
|
@ -189,7 +189,7 @@ namespace gtsam {
|
|||
|
||||
/* ************************************************************************* */
|
||||
template<class FACTORGRAPH>
|
||||
std::pair<boost::shared_ptr<typename EliminateableFactorGraph<FACTORGRAPH>::BayesTreeType>, boost::shared_ptr<FACTORGRAPH> >
|
||||
std::pair<std::shared_ptr<typename EliminateableFactorGraph<FACTORGRAPH>::BayesTreeType>, std::shared_ptr<FACTORGRAPH> >
|
||||
EliminateableFactorGraph<FACTORGRAPH>::eliminatePartialMultifrontal(
|
||||
const Ordering& ordering, const Eliminate& function, OptionalVariableIndex variableIndex) const
|
||||
{
|
||||
|
@ -208,7 +208,7 @@ namespace gtsam {
|
|||
|
||||
/* ************************************************************************* */
|
||||
template<class FACTORGRAPH>
|
||||
std::pair<boost::shared_ptr<typename EliminateableFactorGraph<FACTORGRAPH>::BayesTreeType>, boost::shared_ptr<FACTORGRAPH> >
|
||||
std::pair<std::shared_ptr<typename EliminateableFactorGraph<FACTORGRAPH>::BayesTreeType>, std::shared_ptr<FACTORGRAPH> >
|
||||
EliminateableFactorGraph<FACTORGRAPH>::eliminatePartialMultifrontal(
|
||||
const KeyVector& variables, const Eliminate& function, OptionalVariableIndex variableIndex) const
|
||||
{
|
||||
|
@ -229,7 +229,7 @@ namespace gtsam {
|
|||
|
||||
/* ************************************************************************* */
|
||||
template<class FACTORGRAPH>
|
||||
boost::shared_ptr<typename EliminateableFactorGraph<FACTORGRAPH>::BayesNetType>
|
||||
std::shared_ptr<typename EliminateableFactorGraph<FACTORGRAPH>::BayesNetType>
|
||||
EliminateableFactorGraph<FACTORGRAPH>::marginalMultifrontalBayesNet(
|
||||
boost::variant<const Ordering&, const KeyVector&> variables,
|
||||
const Eliminate& function, OptionalVariableIndex variableIndex) const
|
||||
|
@ -261,7 +261,7 @@ namespace gtsam {
|
|||
|
||||
/* ************************************************************************* */
|
||||
template<class FACTORGRAPH>
|
||||
boost::shared_ptr<typename EliminateableFactorGraph<FACTORGRAPH>::BayesNetType>
|
||||
std::shared_ptr<typename EliminateableFactorGraph<FACTORGRAPH>::BayesNetType>
|
||||
EliminateableFactorGraph<FACTORGRAPH>::marginalMultifrontalBayesNet(
|
||||
boost::variant<const Ordering&, const KeyVector&> variables,
|
||||
const Ordering& marginalizedVariableOrdering,
|
||||
|
@ -275,8 +275,8 @@ namespace gtsam {
|
|||
gttic(marginalMultifrontalBayesNet);
|
||||
// An ordering was provided for the marginalized variables, so we can first eliminate them
|
||||
// in the order requested.
|
||||
boost::shared_ptr<BayesTreeType> bayesTree;
|
||||
boost::shared_ptr<FactorGraphType> factorGraph;
|
||||
std::shared_ptr<BayesTreeType> bayesTree;
|
||||
std::shared_ptr<FactorGraphType> factorGraph;
|
||||
boost::tie(bayesTree,factorGraph) =
|
||||
eliminatePartialMultifrontal(marginalizedVariableOrdering, function, variableIndex);
|
||||
|
||||
|
@ -296,7 +296,7 @@ namespace gtsam {
|
|||
|
||||
/* ************************************************************************* */
|
||||
template<class FACTORGRAPH>
|
||||
boost::shared_ptr<typename EliminateableFactorGraph<FACTORGRAPH>::BayesTreeType>
|
||||
std::shared_ptr<typename EliminateableFactorGraph<FACTORGRAPH>::BayesTreeType>
|
||||
EliminateableFactorGraph<FACTORGRAPH>::marginalMultifrontalBayesTree(
|
||||
boost::variant<const Ordering&, const KeyVector&> variables,
|
||||
const Eliminate& function, OptionalVariableIndex variableIndex) const
|
||||
|
@ -328,7 +328,7 @@ namespace gtsam {
|
|||
|
||||
/* ************************************************************************* */
|
||||
template<class FACTORGRAPH>
|
||||
boost::shared_ptr<typename EliminateableFactorGraph<FACTORGRAPH>::BayesTreeType>
|
||||
std::shared_ptr<typename EliminateableFactorGraph<FACTORGRAPH>::BayesTreeType>
|
||||
EliminateableFactorGraph<FACTORGRAPH>::marginalMultifrontalBayesTree(
|
||||
boost::variant<const Ordering&, const KeyVector&> variables,
|
||||
const Ordering& marginalizedVariableOrdering,
|
||||
|
@ -342,8 +342,8 @@ namespace gtsam {
|
|||
gttic(marginalMultifrontalBayesTree);
|
||||
// An ordering was provided for the marginalized variables, so we can first eliminate them
|
||||
// in the order requested.
|
||||
boost::shared_ptr<BayesTreeType> bayesTree;
|
||||
boost::shared_ptr<FactorGraphType> factorGraph;
|
||||
std::shared_ptr<BayesTreeType> bayesTree;
|
||||
std::shared_ptr<FactorGraphType> factorGraph;
|
||||
boost::tie(bayesTree,factorGraph) =
|
||||
eliminatePartialMultifrontal(marginalizedVariableOrdering, function, variableIndex);
|
||||
|
||||
|
@ -363,7 +363,7 @@ namespace gtsam {
|
|||
|
||||
/* ************************************************************************* */
|
||||
template<class FACTORGRAPH>
|
||||
boost::shared_ptr<FACTORGRAPH>
|
||||
std::shared_ptr<FACTORGRAPH>
|
||||
EliminateableFactorGraph<FACTORGRAPH>::marginal(
|
||||
const KeyVector& variables,
|
||||
const Eliminate& function, OptionalVariableIndex variableIndex) const
|
||||
|
|
|
@ -18,7 +18,7 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#include <boost/shared_ptr.hpp>
|
||||
#include <memory>
|
||||
#include <cstddef>
|
||||
#include <functional>
|
||||
#include <optional>
|
||||
|
@ -84,7 +84,7 @@ namespace gtsam {
|
|||
|
||||
/// The pair of conditional and remaining factor produced by a single dense elimination step on
|
||||
/// a subgraph.
|
||||
typedef std::pair<boost::shared_ptr<ConditionalType>, boost::shared_ptr<_FactorType> > EliminationResult;
|
||||
typedef std::pair<std::shared_ptr<ConditionalType>, std::shared_ptr<_FactorType> > EliminationResult;
|
||||
|
||||
/// The function type that does a single dense elimination step on a subgraph.
|
||||
typedef std::function<EliminationResult(const FactorGraphType&, const Ordering&)> Eliminate;
|
||||
|
@ -101,22 +101,22 @@ namespace gtsam {
|
|||
*
|
||||
* <b> Example - Full Cholesky elimination in COLAMD order: </b>
|
||||
* \code
|
||||
* boost::shared_ptr<GaussianBayesNet> result = graph.eliminateSequential(EliminateCholesky);
|
||||
* std::shared_ptr<GaussianBayesNet> result = graph.eliminateSequential(EliminateCholesky);
|
||||
* \endcode
|
||||
*
|
||||
* <b> Example - METIS ordering for elimination
|
||||
* \code
|
||||
* boost::shared_ptr<GaussianBayesNet> result = graph.eliminateSequential(OrderingType::METIS);
|
||||
* std::shared_ptr<GaussianBayesNet> result = graph.eliminateSequential(OrderingType::METIS);
|
||||
* \endcode
|
||||
*
|
||||
* <b> Example - Reusing an existing VariableIndex to improve performance, and using COLAMD ordering: </b>
|
||||
* \code
|
||||
* VariableIndex varIndex(graph); // Build variable index
|
||||
* Data data = otherFunctionUsingVariableIndex(graph, varIndex); // Other code that uses variable index
|
||||
* boost::shared_ptr<GaussianBayesNet> result = graph.eliminateSequential(EliminateQR, varIndex, std::nullopt);
|
||||
* std::shared_ptr<GaussianBayesNet> result = graph.eliminateSequential(EliminateQR, varIndex, std::nullopt);
|
||||
* \endcode
|
||||
* */
|
||||
boost::shared_ptr<BayesNetType> eliminateSequential(
|
||||
std::shared_ptr<BayesNetType> eliminateSequential(
|
||||
OptionalOrderingType orderingType = {},
|
||||
const Eliminate& function = EliminationTraitsType::DefaultEliminate,
|
||||
OptionalVariableIndex variableIndex = {}) const;
|
||||
|
@ -125,17 +125,17 @@ namespace gtsam {
|
|||
*
|
||||
* <b> Example - Full QR elimination in specified order:
|
||||
* \code
|
||||
* boost::shared_ptr<GaussianBayesNet> result = graph.eliminateSequential(myOrdering, EliminateQR);
|
||||
* std::shared_ptr<GaussianBayesNet> result = graph.eliminateSequential(myOrdering, EliminateQR);
|
||||
* \endcode
|
||||
*
|
||||
* <b> Example - Reusing an existing VariableIndex to improve performance: </b>
|
||||
* \code
|
||||
* VariableIndex varIndex(graph); // Build variable index
|
||||
* Data data = otherFunctionUsingVariableIndex(graph, varIndex); // Other code that uses variable index
|
||||
* boost::shared_ptr<GaussianBayesNet> result = graph.eliminateSequential(myOrdering, EliminateQR, varIndex, std::nullopt);
|
||||
* std::shared_ptr<GaussianBayesNet> result = graph.eliminateSequential(myOrdering, EliminateQR, varIndex, std::nullopt);
|
||||
* \endcode
|
||||
* */
|
||||
boost::shared_ptr<BayesNetType> eliminateSequential(
|
||||
std::shared_ptr<BayesNetType> eliminateSequential(
|
||||
const Ordering& ordering,
|
||||
const Eliminate& function = EliminationTraitsType::DefaultEliminate,
|
||||
OptionalVariableIndex variableIndex = {}) const;
|
||||
|
@ -146,17 +146,17 @@ namespace gtsam {
|
|||
*
|
||||
* <b> Example - Full Cholesky elimination in COLAMD order: </b>
|
||||
* \code
|
||||
* boost::shared_ptr<GaussianBayesTree> result = graph.eliminateMultifrontal(EliminateCholesky);
|
||||
* std::shared_ptr<GaussianBayesTree> result = graph.eliminateMultifrontal(EliminateCholesky);
|
||||
* \endcode
|
||||
*
|
||||
* <b> Example - Reusing an existing VariableIndex to improve performance, and using COLAMD ordering: </b>
|
||||
* \code
|
||||
* VariableIndex varIndex(graph); // Build variable index
|
||||
* Data data = otherFunctionUsingVariableIndex(graph, varIndex); // Other code that uses variable index
|
||||
* boost::shared_ptr<GaussianBayesTree> result = graph.eliminateMultifrontal(EliminateQR, {}, varIndex);
|
||||
* std::shared_ptr<GaussianBayesTree> result = graph.eliminateMultifrontal(EliminateQR, {}, varIndex);
|
||||
* \endcode
|
||||
* */
|
||||
boost::shared_ptr<BayesTreeType> eliminateMultifrontal(
|
||||
std::shared_ptr<BayesTreeType> eliminateMultifrontal(
|
||||
OptionalOrderingType orderingType = {},
|
||||
const Eliminate& function = EliminationTraitsType::DefaultEliminate,
|
||||
OptionalVariableIndex variableIndex = {}) const;
|
||||
|
@ -167,10 +167,10 @@ namespace gtsam {
|
|||
*
|
||||
* <b> Example - Full QR elimination in specified order:
|
||||
* \code
|
||||
* boost::shared_ptr<GaussianBayesTree> result = graph.eliminateMultifrontal(EliminateQR, myOrdering);
|
||||
* std::shared_ptr<GaussianBayesTree> result = graph.eliminateMultifrontal(EliminateQR, myOrdering);
|
||||
* \endcode
|
||||
* */
|
||||
boost::shared_ptr<BayesTreeType> eliminateMultifrontal(
|
||||
std::shared_ptr<BayesTreeType> eliminateMultifrontal(
|
||||
const Ordering& ordering,
|
||||
const Eliminate& function = EliminationTraitsType::DefaultEliminate,
|
||||
OptionalVariableIndex variableIndex = {}) const;
|
||||
|
@ -179,7 +179,7 @@ namespace gtsam {
|
|||
* and a remaining factor graph. This computes the factorization \f$ p(X) = p(A|B) p(B) \f$,
|
||||
* where \f$ A = \f$ \c variables, \f$ X \f$ is all the variables in the factor graph, and \f$
|
||||
* B = X\backslash A \f$. */
|
||||
std::pair<boost::shared_ptr<BayesNetType>, boost::shared_ptr<FactorGraphType> >
|
||||
std::pair<std::shared_ptr<BayesNetType>, std::shared_ptr<FactorGraphType> >
|
||||
eliminatePartialSequential(
|
||||
const Ordering& ordering,
|
||||
const Eliminate& function = EliminationTraitsType::DefaultEliminate,
|
||||
|
@ -189,7 +189,7 @@ namespace gtsam {
|
|||
* produce a Bayes net and a remaining factor graph. This computes the factorization \f$ p(X)
|
||||
* = p(A|B) p(B) \f$, where \f$ A = \f$ \c variables, \f$ X \f$ is all the variables in the
|
||||
* factor graph, and \f$ B = X\backslash A \f$. */
|
||||
std::pair<boost::shared_ptr<BayesNetType>, boost::shared_ptr<FactorGraphType> >
|
||||
std::pair<std::shared_ptr<BayesNetType>, std::shared_ptr<FactorGraphType> >
|
||||
eliminatePartialSequential(
|
||||
const KeyVector& variables,
|
||||
const Eliminate& function = EliminationTraitsType::DefaultEliminate,
|
||||
|
@ -199,7 +199,7 @@ namespace gtsam {
|
|||
* tree and a remaining factor graph. This computes the factorization \f$ p(X) = p(A|B) p(B)
|
||||
* \f$, where \f$ A = \f$ \c variables, \f$ X \f$ is all the variables in the factor graph, and
|
||||
* \f$ B = X\backslash A \f$. */
|
||||
std::pair<boost::shared_ptr<BayesTreeType>, boost::shared_ptr<FactorGraphType> >
|
||||
std::pair<std::shared_ptr<BayesTreeType>, std::shared_ptr<FactorGraphType> >
|
||||
eliminatePartialMultifrontal(
|
||||
const Ordering& ordering,
|
||||
const Eliminate& function = EliminationTraitsType::DefaultEliminate,
|
||||
|
@ -209,7 +209,7 @@ namespace gtsam {
|
|||
* produce a Bayes tree and a remaining factor graph. This computes the factorization \f$ p(X)
|
||||
* = p(A|B) p(B) \f$, where \f$ A = \f$ \c variables, \f$ X \f$ is all the variables in the
|
||||
* factor graph, and \f$ B = X\backslash A \f$. */
|
||||
std::pair<boost::shared_ptr<BayesTreeType>, boost::shared_ptr<FactorGraphType> >
|
||||
std::pair<std::shared_ptr<BayesTreeType>, std::shared_ptr<FactorGraphType> >
|
||||
eliminatePartialMultifrontal(
|
||||
const KeyVector& variables,
|
||||
const Eliminate& function = EliminationTraitsType::DefaultEliminate,
|
||||
|
@ -224,7 +224,7 @@ namespace gtsam {
|
|||
* used.
|
||||
* @param variableIndex Optional pre-computed VariableIndex for the factor graph, if not
|
||||
* provided one will be computed. */
|
||||
boost::shared_ptr<BayesNetType> marginalMultifrontalBayesNet(
|
||||
std::shared_ptr<BayesNetType> marginalMultifrontalBayesNet(
|
||||
boost::variant<const Ordering&, const KeyVector&> variables,
|
||||
const Eliminate& function = EliminationTraitsType::DefaultEliminate,
|
||||
OptionalVariableIndex variableIndex = {}) const;
|
||||
|
@ -239,7 +239,7 @@ namespace gtsam {
|
|||
* used.
|
||||
* @param variableIndex Optional pre-computed VariableIndex for the factor graph, if not
|
||||
* provided one will be computed. */
|
||||
boost::shared_ptr<BayesNetType> marginalMultifrontalBayesNet(
|
||||
std::shared_ptr<BayesNetType> marginalMultifrontalBayesNet(
|
||||
boost::variant<const Ordering&, const KeyVector&> variables,
|
||||
const Ordering& marginalizedVariableOrdering,
|
||||
const Eliminate& function = EliminationTraitsType::DefaultEliminate,
|
||||
|
@ -254,7 +254,7 @@ namespace gtsam {
|
|||
* used.
|
||||
* @param variableIndex Optional pre-computed VariableIndex for the factor graph, if not
|
||||
* provided one will be computed. */
|
||||
boost::shared_ptr<BayesTreeType> marginalMultifrontalBayesTree(
|
||||
std::shared_ptr<BayesTreeType> marginalMultifrontalBayesTree(
|
||||
boost::variant<const Ordering&, const KeyVector&> variables,
|
||||
const Eliminate& function = EliminationTraitsType::DefaultEliminate,
|
||||
OptionalVariableIndex variableIndex = {}) const;
|
||||
|
@ -269,14 +269,14 @@ namespace gtsam {
|
|||
* used.
|
||||
* @param variableIndex Optional pre-computed VariableIndex for the factor graph, if not
|
||||
* provided one will be computed. */
|
||||
boost::shared_ptr<BayesTreeType> marginalMultifrontalBayesTree(
|
||||
std::shared_ptr<BayesTreeType> marginalMultifrontalBayesTree(
|
||||
boost::variant<const Ordering&, const KeyVector&> variables,
|
||||
const Ordering& marginalizedVariableOrdering,
|
||||
const Eliminate& function = EliminationTraitsType::DefaultEliminate,
|
||||
OptionalVariableIndex variableIndex = {}) const;
|
||||
|
||||
/** Compute the marginal factor graph of the requested variables. */
|
||||
boost::shared_ptr<FactorGraphType> marginal(
|
||||
std::shared_ptr<FactorGraphType> marginal(
|
||||
const KeyVector& variables,
|
||||
const Eliminate& function = EliminationTraitsType::DefaultEliminate,
|
||||
OptionalVariableIndex variableIndex = {}) const;
|
||||
|
|
|
@ -33,7 +33,7 @@ namespace gtsam {
|
|||
template<class BAYESNET, class GRAPH>
|
||||
typename EliminationTree<BAYESNET,GRAPH>::sharedFactor
|
||||
EliminationTree<BAYESNET,GRAPH>::Node::eliminate(
|
||||
const boost::shared_ptr<BayesNetType>& output,
|
||||
const std::shared_ptr<BayesNetType>& output,
|
||||
const Eliminate& function, const FastVector<sharedFactor>& childrenResults) const
|
||||
{
|
||||
// This function eliminates one node (Node::eliminate) - see below eliminate for the whole tree.
|
||||
|
@ -98,7 +98,7 @@ namespace gtsam {
|
|||
{
|
||||
// Retrieve the factors involving this variable and create the current node
|
||||
const FactorIndices& factors = structure[order[j]];
|
||||
const sharedNode node = boost::make_shared<Node>();
|
||||
const sharedNode node = std::make_shared<Node>();
|
||||
node->key = order[j];
|
||||
|
||||
// for row i \in Struct[A*j] do
|
||||
|
@ -183,18 +183,18 @@ namespace gtsam {
|
|||
|
||||
/* ************************************************************************* */
|
||||
template<class BAYESNET, class GRAPH>
|
||||
std::pair<boost::shared_ptr<BAYESNET>, boost::shared_ptr<GRAPH> >
|
||||
std::pair<std::shared_ptr<BAYESNET>, std::shared_ptr<GRAPH> >
|
||||
EliminationTree<BAYESNET,GRAPH>::eliminate(Eliminate function) const
|
||||
{
|
||||
gttic(EliminationTree_eliminate);
|
||||
// Allocate result
|
||||
auto result = boost::make_shared<BayesNetType>();
|
||||
auto result = std::make_shared<BayesNetType>();
|
||||
|
||||
// Run tree elimination algorithm
|
||||
FastVector<sharedFactor> remainingFactors = inference::EliminateTree(result, *this, function);
|
||||
|
||||
// Add remaining factors that were not involved with eliminated variables
|
||||
auto allRemainingFactors = boost::make_shared<FactorGraphType>();
|
||||
auto allRemainingFactors = std::make_shared<FactorGraphType>();
|
||||
allRemainingFactors->push_back(remainingFactors_.begin(), remainingFactors_.end());
|
||||
allRemainingFactors->push_back(remainingFactors.begin(), remainingFactors.end());
|
||||
|
||||
|
|
|
@ -18,7 +18,7 @@
|
|||
#pragma once
|
||||
|
||||
#include <utility>
|
||||
#include <boost/shared_ptr.hpp>
|
||||
#include <memory>
|
||||
|
||||
#include <gtsam/base/Testable.h>
|
||||
#include <gtsam/base/FastVector.h>
|
||||
|
@ -52,32 +52,32 @@ namespace gtsam {
|
|||
{
|
||||
protected:
|
||||
typedef EliminationTree<BAYESNET, GRAPH> 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
|
||||
|
||||
public:
|
||||
typedef GRAPH FactorGraphType; ///< The factor graph type
|
||||
typedef typename GRAPH::FactorType FactorType; ///< The type of factors
|
||||
typedef typename boost::shared_ptr<FactorType> sharedFactor; ///< Shared pointer to a factor
|
||||
typedef typename std::shared_ptr<FactorType> sharedFactor; ///< Shared pointer to a factor
|
||||
typedef BAYESNET BayesNetType; ///< The BayesNet corresponding to FACTOR
|
||||
typedef typename BayesNetType::ConditionalType ConditionalType; ///< The type of conditionals
|
||||
typedef typename boost::shared_ptr<ConditionalType> sharedConditional; ///< Shared pointer to a conditional
|
||||
typedef typename std::shared_ptr<ConditionalType> sharedConditional; ///< Shared pointer to a conditional
|
||||
typedef typename GRAPH::Eliminate Eliminate;
|
||||
|
||||
struct Node {
|
||||
typedef FastVector<sharedFactor> Factors;
|
||||
typedef FastVector<boost::shared_ptr<Node> > Children;
|
||||
typedef FastVector<std::shared_ptr<Node> > Children;
|
||||
|
||||
Key key; ///< key associated with root
|
||||
Factors factors; ///< factors associated with root
|
||||
Children children; ///< sub-trees
|
||||
|
||||
sharedFactor eliminate(const boost::shared_ptr<BayesNetType>& output,
|
||||
sharedFactor eliminate(const std::shared_ptr<BayesNetType>& output,
|
||||
const Eliminate& function, const FastVector<sharedFactor>& childrenFactors) const;
|
||||
|
||||
void print(const std::string& str, const KeyFormatter& keyFormatter) const;
|
||||
};
|
||||
|
||||
typedef boost::shared_ptr<Node> sharedNode; ///< Shared pointer to Node
|
||||
typedef std::shared_ptr<Node> sharedNode; ///< Shared pointer to Node
|
||||
|
||||
protected:
|
||||
/** concept check */
|
||||
|
@ -126,7 +126,7 @@ namespace gtsam {
|
|||
* in GaussianFactorGraph.h
|
||||
* @return The Bayes net and factor graph resulting from elimination
|
||||
*/
|
||||
std::pair<boost::shared_ptr<BayesNetType>, boost::shared_ptr<FactorGraphType> >
|
||||
std::pair<std::shared_ptr<BayesNetType>, std::shared_ptr<FactorGraphType> >
|
||||
eliminate(Eliminate function) const;
|
||||
|
||||
/// @}
|
||||
|
|
Some files were not shown because too many files have changed in this diff Show More
Loading…
Reference in New Issue