remove trailing spaces
parent
c84496632f
commit
1cdc228d6a
|
@ -1,6 +1,6 @@
|
|||
/* ----------------------------------------------------------------------------
|
||||
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* Atlanta, Georgia 30332-0415
|
||||
* All Rights Reserved
|
||||
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/* ----------------------------------------------------------------------------
|
||||
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* Atlanta, Georgia 30332-0415
|
||||
* All Rights Reserved
|
||||
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
|
||||
|
@ -36,7 +36,7 @@ Test *Test::getNext() const
|
|||
}
|
||||
|
||||
void Test::setNext(Test *test)
|
||||
{
|
||||
{
|
||||
next_ = test;
|
||||
}
|
||||
|
||||
|
@ -46,9 +46,9 @@ bool Test::check(long expected, long actual, TestResult& result, const std::stri
|
|||
return true;
|
||||
result.addFailure (
|
||||
Failure (
|
||||
name_,
|
||||
name_,
|
||||
boost::lexical_cast<std::string> (__FILE__),
|
||||
__LINE__,
|
||||
__LINE__,
|
||||
boost::lexical_cast<std::string> (expected),
|
||||
boost::lexical_cast<std::string> (actual)));
|
||||
|
||||
|
@ -63,10 +63,10 @@ bool Test::check(const std::string& expected, const std::string& actual, TestRes
|
|||
return true;
|
||||
result.addFailure (
|
||||
Failure (
|
||||
name_,
|
||||
name_,
|
||||
boost::lexical_cast<std::string> (__FILE__),
|
||||
__LINE__,
|
||||
expected,
|
||||
__LINE__,
|
||||
expected,
|
||||
actual));
|
||||
|
||||
return false;
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/* ----------------------------------------------------------------------------
|
||||
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* Atlanta, Georgia 30332-0415
|
||||
* All Rights Reserved
|
||||
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
|
||||
|
@ -12,7 +12,7 @@
|
|||
///////////////////////////////////////////////////////////////////////////////
|
||||
//
|
||||
// TEST.H
|
||||
//
|
||||
//
|
||||
// This file contains the Test class along with the macros which make effective
|
||||
// in the harness.
|
||||
//
|
||||
|
@ -66,7 +66,7 @@ protected:
|
|||
virtual ~testGroup##testName##Test () {};\
|
||||
void run (TestResult& result_);} \
|
||||
testGroup##testName##Instance; \
|
||||
void testGroup##testName##Test::run (TestResult& result_)
|
||||
void testGroup##testName##Test::run (TestResult& result_)
|
||||
|
||||
/**
|
||||
* Declare friend in a class to test its private methods
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/* ----------------------------------------------------------------------------
|
||||
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* Atlanta, Georgia 30332-0415
|
||||
* All Rights Reserved
|
||||
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
|
||||
|
@ -12,7 +12,7 @@
|
|||
///////////////////////////////////////////////////////////////////////////////
|
||||
//
|
||||
// TESTHARNESS.H
|
||||
//
|
||||
//
|
||||
// The primary include file for the framework.
|
||||
//
|
||||
///////////////////////////////////////////////////////////////////////////////
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/* ----------------------------------------------------------------------------
|
||||
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* Atlanta, Georgia 30332-0415
|
||||
* All Rights Reserved
|
||||
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
|
||||
|
@ -18,26 +18,26 @@
|
|||
#include "TestResult.h"
|
||||
#include "TestRegistry.h"
|
||||
|
||||
void TestRegistry::addTest (Test *test)
|
||||
void TestRegistry::addTest (Test *test)
|
||||
{
|
||||
instance ().add (test);
|
||||
}
|
||||
|
||||
|
||||
int TestRegistry::runAllTests (TestResult& result)
|
||||
int TestRegistry::runAllTests (TestResult& result)
|
||||
{
|
||||
return instance ().run (result);
|
||||
}
|
||||
|
||||
|
||||
TestRegistry& TestRegistry::instance ()
|
||||
TestRegistry& TestRegistry::instance ()
|
||||
{
|
||||
static TestRegistry registry;
|
||||
return registry;
|
||||
}
|
||||
|
||||
|
||||
void TestRegistry::add (Test *test)
|
||||
void TestRegistry::add (Test *test)
|
||||
{
|
||||
if (tests == 0) {
|
||||
test->setNext(0);
|
||||
|
@ -52,7 +52,7 @@ void TestRegistry::add (Test *test)
|
|||
}
|
||||
|
||||
|
||||
int TestRegistry::run (TestResult& result)
|
||||
int TestRegistry::run (TestResult& result)
|
||||
{
|
||||
result.testsStarted ();
|
||||
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/* ----------------------------------------------------------------------------
|
||||
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* Atlanta, Georgia 30332-0415
|
||||
* All Rights Reserved
|
||||
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
|
||||
|
@ -12,9 +12,9 @@
|
|||
///////////////////////////////////////////////////////////////////////////////
|
||||
//
|
||||
// TESTREGISTRY.H
|
||||
//
|
||||
// TestRegistry is a singleton collection of all the tests to run in a system.
|
||||
//
|
||||
//
|
||||
// TestRegistry is a singleton collection of all the tests to run in a system.
|
||||
//
|
||||
///////////////////////////////////////////////////////////////////////////////
|
||||
|
||||
#ifndef TESTREGISTRY_H
|
||||
|
@ -38,7 +38,7 @@ private:
|
|||
void add (Test *test);
|
||||
int run (TestResult& result);
|
||||
|
||||
|
||||
|
||||
Test *tests;
|
||||
Test *lastTest;
|
||||
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/* ----------------------------------------------------------------------------
|
||||
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* Atlanta, Georgia 30332-0415
|
||||
* All Rights Reserved
|
||||
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
|
||||
|
@ -22,12 +22,12 @@ TestResult::TestResult ()
|
|||
}
|
||||
|
||||
|
||||
void TestResult::testsStarted ()
|
||||
void TestResult::testsStarted ()
|
||||
{
|
||||
}
|
||||
|
||||
|
||||
void TestResult::addFailure (const Failure& failure)
|
||||
void TestResult::addFailure (const Failure& failure)
|
||||
{
|
||||
if (failure.lineNumber < 0) // allow for no line number
|
||||
fprintf (stdout, "%s%s%s%s\n",
|
||||
|
@ -48,7 +48,7 @@ void TestResult::addFailure (const Failure& failure)
|
|||
}
|
||||
|
||||
|
||||
void TestResult::testsEnded ()
|
||||
void TestResult::testsEnded ()
|
||||
{
|
||||
if (failureCount > 0)
|
||||
fprintf (stdout, "There were %d failures\n", failureCount);
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/* ----------------------------------------------------------------------------
|
||||
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* Atlanta, Georgia 30332-0415
|
||||
* All Rights Reserved
|
||||
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
|
||||
|
@ -12,10 +12,10 @@
|
|||
///////////////////////////////////////////////////////////////////////////////
|
||||
//
|
||||
// TESTRESULT.H
|
||||
//
|
||||
//
|
||||
// A TestResult is a collection of the history of some test runs. Right now
|
||||
// it just collects failures.
|
||||
//
|
||||
//
|
||||
///////////////////////////////////////////////////////////////////////////////
|
||||
|
||||
#ifndef TESTRESULT_H
|
||||
|
@ -26,12 +26,12 @@ class Failure;
|
|||
class TestResult
|
||||
{
|
||||
public:
|
||||
TestResult ();
|
||||
TestResult ();
|
||||
virtual ~TestResult() {};
|
||||
virtual void testsStarted ();
|
||||
virtual void addFailure (const Failure& failure);
|
||||
virtual void testsEnded ();
|
||||
|
||||
|
||||
int getFailureCount() {return failureCount;}
|
||||
|
||||
private:
|
||||
|
|
|
@ -35,7 +35,7 @@ inline PyArrayObject *_ndarray_view<double>(double *data, long rows, long cols,
|
|||
return ndarray_double_C(data, rows, cols, outer_stride>0?outer_stride:cols, inner_stride>0?inner_stride:1);
|
||||
} else {
|
||||
// Eigen column-major mode: row_stride=outer_stride, and col_stride=inner_stride
|
||||
// If no stride is given, the cow_stride is set to the number of rows.
|
||||
// If no stride is given, the cow_stride is set to the number of rows.
|
||||
return ndarray_double_F(data, rows, cols, inner_stride>0?inner_stride:1, outer_stride>0?outer_stride:rows);
|
||||
}
|
||||
}
|
||||
|
@ -355,7 +355,7 @@ public:
|
|||
FlattenedMap()
|
||||
: Base(NULL, 0, 0),
|
||||
object_(NULL) {}
|
||||
|
||||
|
||||
FlattenedMap(Scalar *data, long rows, long cols, long outer_stride=0, long inner_stride=0)
|
||||
: Base(data, rows, cols,
|
||||
Eigen::Stride<_StrideOuter, _StrideInner>(outer_stride, inner_stride)),
|
||||
|
@ -363,7 +363,7 @@ public:
|
|||
}
|
||||
|
||||
FlattenedMap(PyArrayObject *object)
|
||||
: Base((Scalar *)((PyArrayObject*)object)->data,
|
||||
: Base((Scalar *)((PyArrayObject*)object)->data,
|
||||
// : Base(_from_numpy<Scalar>((PyArrayObject*)object),
|
||||
(((PyArrayObject*)object)->nd == 2) ? ((PyArrayObject*)object)->dimensions[0] : 1,
|
||||
(((PyArrayObject*)object)->nd == 2) ? ((PyArrayObject*)object)->dimensions[1] : ((PyArrayObject*)object)->dimensions[0],
|
||||
|
@ -390,7 +390,7 @@ public:
|
|||
|
||||
return *this;
|
||||
}
|
||||
|
||||
|
||||
operator Base() const {
|
||||
return static_cast<Base>(*this);
|
||||
}
|
||||
|
@ -429,7 +429,7 @@ public:
|
|||
(ColsAtCompileTime == Eigen::Dynamic) ? 0 : ColsAtCompileTime),
|
||||
object_(NULL) {
|
||||
}
|
||||
|
||||
|
||||
Map(Scalar *data, long rows, long cols)
|
||||
: Base(data, rows, cols),
|
||||
object_(NULL) {}
|
||||
|
@ -456,7 +456,7 @@ public:
|
|||
throw std::invalid_argument("Numpy array must be a in one contiguous segment to be able to be transferred to a Eigen Map.");
|
||||
Py_XINCREF(object_);
|
||||
}
|
||||
|
||||
|
||||
Map &operator=(const Map &other) {
|
||||
if (other.object_) {
|
||||
new (this) Map(other.object_);
|
||||
|
@ -474,7 +474,7 @@ public:
|
|||
MapBase<MatrixType>::operator=(other);
|
||||
return *this;
|
||||
}
|
||||
|
||||
|
||||
operator Base() const {
|
||||
return static_cast<Base>(*this);
|
||||
}
|
||||
|
|
|
@ -1,5 +1,5 @@
|
|||
// add unary measurement factors, like GPS, on all three poses
|
||||
noiseModel::Diagonal::shared_ptr unaryNoise =
|
||||
noiseModel::Diagonal::shared_ptr unaryNoise =
|
||||
noiseModel::Diagonal::Sigmas(Vector2(0.1, 0.1)); // 10cm std on x,y
|
||||
graph.add(boost::make_shared<UnaryFactor>(1, 0.0, 0.0, unaryNoise));
|
||||
graph.add(boost::make_shared<UnaryFactor>(2, 2.0, 0.0, unaryNoise));
|
||||
|
|
|
@ -5,7 +5,7 @@ public:
|
|||
UnaryFactor(Key j, double x, double y, const SharedNoiseModel& model):
|
||||
NoiseModelFactor1<Pose2>(model, j), mx_(x), my_(y) {}
|
||||
|
||||
Vector evaluateError(const Pose2& q,
|
||||
Vector evaluateError(const Pose2& q,
|
||||
boost::optional<Matrix&> H = boost::none) const
|
||||
{
|
||||
if (H) (*H) = (Matrix(2,3)<< 1.0,0.0,0.0, 0.0,1.0,0.0).finished();
|
||||
|
|
|
@ -3,13 +3,13 @@ NonlinearFactorGraph graph;
|
|||
|
||||
// Add a Gaussian prior on pose x_1
|
||||
Pose2 priorMean(0.0, 0.0, 0.0);
|
||||
noiseModel::Diagonal::shared_ptr priorNoise =
|
||||
noiseModel::Diagonal::shared_ptr priorNoise =
|
||||
noiseModel::Diagonal::Sigmas(Vector3(0.3, 0.3, 0.1));
|
||||
graph.add(PriorFactor<Pose2>(1, priorMean, priorNoise));
|
||||
|
||||
// Add two odometry factors
|
||||
Pose2 odometry(2.0, 0.0, 0.0);
|
||||
noiseModel::Diagonal::shared_ptr odometryNoise =
|
||||
noiseModel::Diagonal::shared_ptr odometryNoise =
|
||||
noiseModel::Diagonal::Sigmas(Vector3(0.2, 0.2, 0.1));
|
||||
graph.add(BetweenFactor<Pose2>(1, 2, odometry, odometryNoise));
|
||||
graph.add(BetweenFactor<Pose2>(2, 3, odometry, odometryNoise));
|
||||
|
|
|
@ -1,10 +1,10 @@
|
|||
NonlinearFactorGraph graph;
|
||||
noiseModel::Diagonal::shared_ptr priorNoise =
|
||||
noiseModel::Diagonal::shared_ptr priorNoise =
|
||||
noiseModel::Diagonal::Sigmas(Vector3(0.3, 0.3, 0.1));
|
||||
graph.add(PriorFactor<Pose2>(1, Pose2(0, 0, 0), priorNoise));
|
||||
|
||||
// Add odometry factors
|
||||
noiseModel::Diagonal::shared_ptr model =
|
||||
noiseModel::Diagonal::shared_ptr model =
|
||||
noiseModel::Diagonal::Sigmas(Vector3(0.2, 0.2, 0.1));
|
||||
graph.add(BetweenFactor<Pose2>(1, 2, Pose2(2, 0, 0 ), model));
|
||||
graph.add(BetweenFactor<Pose2>(2, 3, Pose2(2, 0, M_PI_2), model));
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/* ----------------------------------------------------------------------------
|
||||
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* Atlanta, Georgia 30332-0415
|
||||
* All Rights Reserved
|
||||
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/* ----------------------------------------------------------------------------
|
||||
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* Atlanta, Georgia 30332-0415
|
||||
* All Rights Reserved
|
||||
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
|
||||
|
|
|
@ -91,7 +91,7 @@ int main(int argc, char* argv[])
|
|||
cout << "initial state:\n" << initial_state.transpose() << "\n\n";
|
||||
|
||||
// Assemble initial quaternion through gtsam constructor ::quaternion(w,x,y,z);
|
||||
Rot3 prior_rotation = Rot3::Quaternion(initial_state(6), initial_state(3),
|
||||
Rot3 prior_rotation = Rot3::Quaternion(initial_state(6), initial_state(3),
|
||||
initial_state(4), initial_state(5));
|
||||
Point3 prior_point(initial_state.head<3>());
|
||||
Pose3 prior_pose(prior_rotation, prior_point);
|
||||
|
@ -102,7 +102,7 @@ int main(int argc, char* argv[])
|
|||
int correction_count = 0;
|
||||
initial_values.insert(X(correction_count), prior_pose);
|
||||
initial_values.insert(V(correction_count), prior_velocity);
|
||||
initial_values.insert(B(correction_count), prior_imu_bias);
|
||||
initial_values.insert(B(correction_count), prior_imu_bias);
|
||||
|
||||
// Assemble prior noise model and add it the graph.
|
||||
noiseModel::Diagonal::shared_ptr pose_noise_model = noiseModel::Diagonal::Sigmas((Vector(6) << 0.01, 0.01, 0.01, 0.5, 0.5, 0.5).finished()); // rad,rad,rad,m, m, m
|
||||
|
@ -138,7 +138,7 @@ int main(int argc, char* argv[])
|
|||
p->biasAccCovariance = bias_acc_cov; // acc bias in continuous
|
||||
p->biasOmegaCovariance = bias_omega_cov; // gyro bias in continuous
|
||||
p->biasAccOmegaInt = bias_acc_omega_int;
|
||||
|
||||
|
||||
#ifdef USE_COMBINED
|
||||
imu_preintegrated_ = new PreintegratedCombinedMeasurements(p, prior_imu_bias);
|
||||
#else
|
||||
|
@ -154,7 +154,7 @@ int main(int argc, char* argv[])
|
|||
double current_position_error = 0.0, current_orientation_error = 0.0;
|
||||
|
||||
double output_time = 0.0;
|
||||
double dt = 0.005; // The real system has noise, but here, results are nearly
|
||||
double dt = 0.005; // The real system has noise, but here, results are nearly
|
||||
// exactly the same, so keeping this for simplicity.
|
||||
|
||||
// All priors have been set up, now iterate through the data file.
|
||||
|
@ -203,8 +203,8 @@ int main(int argc, char* argv[])
|
|||
*preint_imu);
|
||||
graph->add(imu_factor);
|
||||
imuBias::ConstantBias zero_bias(Vector3(0, 0, 0), Vector3(0, 0, 0));
|
||||
graph->add(BetweenFactor<imuBias::ConstantBias>(B(correction_count-1),
|
||||
B(correction_count ),
|
||||
graph->add(BetweenFactor<imuBias::ConstantBias>(B(correction_count-1),
|
||||
B(correction_count ),
|
||||
zero_bias, bias_noise_model));
|
||||
#endif
|
||||
|
||||
|
@ -215,7 +215,7 @@ int main(int argc, char* argv[])
|
|||
gps(2)), // D,
|
||||
correction_noise);
|
||||
graph->add(gps_factor);
|
||||
|
||||
|
||||
// Now optimize and compare results.
|
||||
prop_state = imu_preintegrated_->predict(prev_state, prev_bias);
|
||||
initial_values.insert(X(correction_count), prop_state.pose());
|
||||
|
@ -250,10 +250,10 @@ int main(int argc, char* argv[])
|
|||
// display statistics
|
||||
cout << "Position error:" << current_position_error << "\t " << "Angular error:" << current_orientation_error << "\n";
|
||||
|
||||
fprintf(fp_out, "%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f\n",
|
||||
fprintf(fp_out, "%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f\n",
|
||||
output_time, gtsam_position(0), gtsam_position(1), gtsam_position(2),
|
||||
gtsam_quat.x(), gtsam_quat.y(), gtsam_quat.z(), gtsam_quat.w(),
|
||||
gps(0), gps(1), gps(2),
|
||||
gps(0), gps(1), gps(2),
|
||||
gps_quat.x(), gps_quat.y(), gps_quat.z(), gps_quat.w());
|
||||
|
||||
output_time += 1.0;
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/* ----------------------------------------------------------------------------
|
||||
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* Atlanta, Georgia 30332-0415
|
||||
* All Rights Reserved
|
||||
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/* ----------------------------------------------------------------------------
|
||||
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* Atlanta, Georgia 30332-0415
|
||||
* All Rights Reserved
|
||||
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/* ----------------------------------------------------------------------------
|
||||
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* Atlanta, Georgia 30332-0415
|
||||
* All Rights Reserved
|
||||
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/* ----------------------------------------------------------------------------
|
||||
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* Atlanta, Georgia 30332-0415
|
||||
* All Rights Reserved
|
||||
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
|
||||
|
|
|
@ -34,47 +34,47 @@ int main(int argc, char* argv[]) {
|
|||
// Concatenate poses to create trajectory
|
||||
poses.insert( poses.end(), poses2.begin(), poses2.end() );
|
||||
poses.insert( poses.end(), poses3.begin(), poses3.end() ); // std::vector of Pose3
|
||||
auto points = createPoints(); // std::vector of Point3
|
||||
auto points = createPoints(); // std::vector of Point3
|
||||
|
||||
// (ground-truth) sensor pose in body frame, further an unknown variable
|
||||
Pose3 body_T_sensor_gt(Rot3::RzRyRx(-M_PI_2, 0.0, -M_PI_2), Point3(0.25, -0.10, 1.0));
|
||||
|
||||
|
||||
// The graph
|
||||
ExpressionFactorGraph graph;
|
||||
|
||||
|
||||
// Specify uncertainty on first pose prior and also for between factor (simplicity reasons)
|
||||
auto poseNoise = noiseModel::Diagonal::Sigmas((Vector(6)<<0.3,0.3,0.3,0.1,0.1,0.1).finished());
|
||||
|
||||
|
||||
// Uncertainty bearing range measurement;
|
||||
auto bearingRangeNoise = noiseModel::Diagonal::Sigmas((Vector(3)<<0.01,0.03,0.05).finished());
|
||||
|
||||
|
||||
// Expressions for body-frame at key 0 and sensor-tf
|
||||
Pose3_ x_('x', 0);
|
||||
Pose3_ body_T_sensor_('T', 0);
|
||||
|
||||
|
||||
// Add a prior on the body-pose
|
||||
graph.addExpressionFactor(x_, poses[0], poseNoise);
|
||||
|
||||
graph.addExpressionFactor(x_, poses[0], poseNoise);
|
||||
|
||||
// Simulated measurements from pose
|
||||
for (size_t i = 0; i < poses.size(); ++i) {
|
||||
auto world_T_sensor = poses[i].compose(body_T_sensor_gt);
|
||||
for (size_t j = 0; j < points.size(); ++j) {
|
||||
|
||||
|
||||
// This expression is the key feature of this example: it creates a differentiable expression of the measurement after being displaced by sensor transform.
|
||||
auto prediction_ = Expression<BearingRange3D>( BearingRange3D::Measure, Pose3_('x',i)*body_T_sensor_, Point3_('l',j));
|
||||
|
||||
|
||||
// Create a *perfect* measurement
|
||||
auto measurement = BearingRange3D(world_T_sensor.bearing(points[j]), world_T_sensor.range(points[j]));
|
||||
|
||||
|
||||
// Add factor
|
||||
graph.addExpressionFactor(prediction_, measurement, bearingRangeNoise);
|
||||
}
|
||||
|
||||
|
||||
// and add a between factor to the graph
|
||||
if (i > 0)
|
||||
{
|
||||
// And also we have a *perfect* measurement for the between factor.
|
||||
graph.addExpressionFactor(between(Pose3_('x', i-1),Pose3_('x', i)), poses[i-1].between(poses[i]), poseNoise);
|
||||
graph.addExpressionFactor(between(Pose3_('x', i-1),Pose3_('x', i)), poses[i-1].between(poses[i]), poseNoise);
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -82,12 +82,12 @@ int main(int argc, char* argv[]) {
|
|||
Values initial;
|
||||
Pose3 delta(Rot3::Rodrigues(-0.1, 0.2, 0.25), Point3(0.05, -0.10, 0.20));
|
||||
for (size_t i = 0; i < poses.size(); ++i)
|
||||
initial.insert(Symbol('x', i), poses[i].compose(delta));
|
||||
initial.insert(Symbol('x', i), poses[i].compose(delta));
|
||||
for (size_t j = 0; j < points.size(); ++j)
|
||||
initial.insert<Point3>(Symbol('l', j), points[j] + Point3(-0.25, 0.20, 0.15));
|
||||
|
||||
|
||||
// Initialize body_T_sensor wrongly (because we do not know!)
|
||||
initial.insert<Pose3>(Symbol('T',0), Pose3());
|
||||
initial.insert<Pose3>(Symbol('T',0), Pose3());
|
||||
|
||||
std::cout << "initial error: " << graph.error(initial) << std::endl;
|
||||
Values result = LevenbergMarquardtOptimizer(graph, initial).optimize();
|
||||
|
|
|
@ -52,9 +52,9 @@ std::vector<gtsam::Point3> createPoints() {
|
|||
/* ************************************************************************* */
|
||||
std::vector<gtsam::Pose3> createPoses(
|
||||
const gtsam::Pose3& init = gtsam::Pose3(gtsam::Rot3::Ypr(M_PI/2,0,-M_PI/2), gtsam::Point3(30, 0, 0)),
|
||||
const gtsam::Pose3& delta = gtsam::Pose3(gtsam::Rot3::Ypr(0,-M_PI/4,0), gtsam::Point3(sin(M_PI/4)*30, 0, 30*(1-sin(M_PI/4)))),
|
||||
const gtsam::Pose3& delta = gtsam::Pose3(gtsam::Rot3::Ypr(0,-M_PI/4,0), gtsam::Point3(sin(M_PI/4)*30, 0, 30*(1-sin(M_PI/4)))),
|
||||
int steps = 8) {
|
||||
|
||||
|
||||
// Create the set of ground-truth poses
|
||||
// Default values give a circular trajectory, radius 30 at pi/4 intervals, always facing the circle center
|
||||
std::vector<gtsam::Pose3> poses;
|
||||
|
@ -63,6 +63,6 @@ std::vector<gtsam::Pose3> createPoses(
|
|||
for(; i < steps; ++i) {
|
||||
poses.push_back(poses[i-1].compose(delta));
|
||||
}
|
||||
|
||||
|
||||
return poses;
|
||||
}
|
|
@ -1,6 +1,6 @@
|
|||
/* ----------------------------------------------------------------------------
|
||||
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* Atlanta, Georgia 30332-0415
|
||||
* All Rights Reserved
|
||||
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
|
||||
|
|
|
@ -361,7 +361,7 @@ void runIncremental()
|
|||
const auto& measured = factor->measured();
|
||||
Rot2 measuredBearing = measured.bearing();
|
||||
double measuredRange = measured.range();
|
||||
newVariables.insert(lmKey,
|
||||
newVariables.insert(lmKey,
|
||||
pose.transform_from(measuredBearing.rotate(Point2(measuredRange, 0.0))));
|
||||
}
|
||||
}
|
||||
|
|
|
@ -22,7 +22,7 @@
|
|||
* -moves forward 1 meter
|
||||
* -takes stereo readings on three landmarks
|
||||
*/
|
||||
|
||||
|
||||
#include <gtsam/geometry/Pose3.h>
|
||||
#include <gtsam/geometry/Cal3_S2Stereo.h>
|
||||
#include <gtsam/nonlinear/Values.h>
|
||||
|
@ -40,7 +40,7 @@ int main(int argc, char** argv){
|
|||
NonlinearFactorGraph graph;
|
||||
Pose3 first_pose;
|
||||
graph.emplace_shared<NonlinearEquality<Pose3> >(1, Pose3());
|
||||
|
||||
|
||||
//create factor noise model with 3 sigmas of value 1
|
||||
const noiseModel::Isotropic::shared_ptr model = noiseModel::Isotropic::Sigma(3,1);
|
||||
//create stereo camera calibration object with .2m between cameras
|
||||
|
|
|
@ -50,7 +50,7 @@ int main(int argc, char** argv){
|
|||
string calibration_loc = findExampleDataFile("VO_calibration.txt");
|
||||
string pose_loc = findExampleDataFile("VO_camera_poses_large.txt");
|
||||
string factor_loc = findExampleDataFile("VO_stereo_factors_large.txt");
|
||||
|
||||
|
||||
//read camera calibration info from file
|
||||
// focal lengths fx, fy, skew s, principal point u0, v0, baseline b
|
||||
double fx, fy, s, u0, v0, b;
|
||||
|
@ -60,7 +60,7 @@ int main(int argc, char** argv){
|
|||
|
||||
//create stereo camera calibration object
|
||||
const Cal3_S2Stereo::shared_ptr K(new Cal3_S2Stereo(fx,fy,s,u0,v0,b));
|
||||
|
||||
|
||||
ifstream pose_file(pose_loc.c_str());
|
||||
cout << "Reading camera poses" << endl;
|
||||
int pose_id;
|
||||
|
@ -72,7 +72,7 @@ int main(int argc, char** argv){
|
|||
}
|
||||
initial_estimate.insert(Symbol('x', pose_id), Pose3(m));
|
||||
}
|
||||
|
||||
|
||||
// camera and landmark keys
|
||||
size_t x, l;
|
||||
|
||||
|
|
|
@ -36,7 +36,7 @@ int main(int argc, char** argv) {
|
|||
|
||||
// Each node takes 1 of 7 possible states denoted by 0-6 in following order:
|
||||
// ["VideoGames" "Industry" "GradSchool" "VideoGames(with PhD)"
|
||||
// "Industry(with PhD)" "Academia" "Deceased"]
|
||||
// "Industry(with PhD)" "Academia" "Deceased"]
|
||||
const size_t nrStates = 7;
|
||||
|
||||
// define variables
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/* ----------------------------------------------------------------------------
|
||||
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* Atlanta, Georgia 30332-0415
|
||||
* All Rights Reserved
|
||||
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/* ----------------------------------------------------------------------------
|
||||
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* Atlanta, Georgia 30332-0415
|
||||
* All Rights Reserved
|
||||
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/* ----------------------------------------------------------------------------
|
||||
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* Atlanta, Georgia 30332-0415
|
||||
* All Rights Reserved
|
||||
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/* ----------------------------------------------------------------------------
|
||||
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* Atlanta, Georgia 30332-0415
|
||||
* All Rights Reserved
|
||||
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/* ----------------------------------------------------------------------------
|
||||
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* Atlanta, Georgia 30332-0415
|
||||
* All Rights Reserved
|
||||
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/* ----------------------------------------------------------------------------
|
||||
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* Atlanta, Georgia 30332-0415
|
||||
* All Rights Reserved
|
||||
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/* ----------------------------------------------------------------------------
|
||||
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* Atlanta, Georgia 30332-0415
|
||||
* All Rights Reserved
|
||||
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/* ----------------------------------------------------------------------------
|
||||
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* Atlanta, Georgia 30332-0415
|
||||
* All Rights Reserved
|
||||
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/* ----------------------------------------------------------------------------
|
||||
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* Atlanta, Georgia 30332-0415
|
||||
* All Rights Reserved
|
||||
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
|
||||
|
@ -170,7 +170,7 @@ struct FixedDimension {
|
|||
|
||||
#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4
|
||||
/// Helper class to construct the product manifold of two other manifolds, M1 and M2
|
||||
/// Deprecated because of limited usefulness, maximum obfuscation
|
||||
/// Deprecated because of limited usefulness, maximum obfuscation
|
||||
template<typename M1, typename M2>
|
||||
class ProductManifold: public std::pair<M1, M2> {
|
||||
BOOST_CONCEPT_ASSERT((IsManifold<M1>));
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/* ----------------------------------------------------------------------------
|
||||
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* Atlanta, Georgia 30332-0415
|
||||
* All Rights Reserved
|
||||
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
|
||||
|
@ -540,7 +540,7 @@ Matrix cholesky_inverse(const Matrix &A)
|
|||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
// Semantics:
|
||||
// Semantics:
|
||||
// if B = inverse_square_root(A), then all of the following are true:
|
||||
// inv(B) * inv(B)' == A
|
||||
// inv(B' * B) == A
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/* ----------------------------------------------------------------------------
|
||||
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* Atlanta, Georgia 30332-0415
|
||||
* All Rights Reserved
|
||||
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/* ----------------------------------------------------------------------------
|
||||
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* Atlanta, Georgia 30332-0415
|
||||
* All Rights Reserved
|
||||
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/* ----------------------------------------------------------------------------
|
||||
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* Atlanta, Georgia 30332-0415
|
||||
* All Rights Reserved
|
||||
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/* ----------------------------------------------------------------------------
|
||||
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* Atlanta, Georgia 30332-0415
|
||||
* All Rights Reserved
|
||||
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/* ----------------------------------------------------------------------------
|
||||
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* Atlanta, Georgia 30332-0415
|
||||
* All Rights Reserved
|
||||
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/* ----------------------------------------------------------------------------
|
||||
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* Atlanta, Georgia 30332-0415
|
||||
* All Rights Reserved
|
||||
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/* ----------------------------------------------------------------------------
|
||||
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* Atlanta, Georgia 30332-0415
|
||||
* All Rights Reserved
|
||||
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/* ----------------------------------------------------------------------------
|
||||
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* Atlanta, Georgia 30332-0415
|
||||
* All Rights Reserved
|
||||
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/* ----------------------------------------------------------------------------
|
||||
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* Atlanta, Georgia 30332-0415
|
||||
* All Rights Reserved
|
||||
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/* ----------------------------------------------------------------------------
|
||||
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* Atlanta, Georgia 30332-0415
|
||||
* All Rights Reserved
|
||||
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/* ----------------------------------------------------------------------------
|
||||
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* Atlanta, Georgia 30332-0415
|
||||
* All Rights Reserved
|
||||
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
|
||||
|
@ -36,7 +36,7 @@ struct GTSAM_EXPORT LieVector : public Vector {
|
|||
|
||||
/** initialize from a normal vector */
|
||||
LieVector(const Vector& v) : Vector(v) {}
|
||||
|
||||
|
||||
template <class V>
|
||||
LieVector(const V& v) : Vector(v) {}
|
||||
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/* ----------------------------------------------------------------------------
|
||||
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* Atlanta, Georgia 30332-0415
|
||||
* All Rights Reserved
|
||||
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/* ----------------------------------------------------------------------------
|
||||
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* Atlanta, Georgia 30332-0415
|
||||
* All Rights Reserved
|
||||
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/* ----------------------------------------------------------------------------
|
||||
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* Atlanta, Georgia 30332-0415
|
||||
* All Rights Reserved
|
||||
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/* ----------------------------------------------------------------------------
|
||||
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* Atlanta, Georgia 30332-0415
|
||||
* All Rights Reserved
|
||||
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/* ----------------------------------------------------------------------------
|
||||
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* Atlanta, Georgia 30332-0415
|
||||
* All Rights Reserved
|
||||
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/* ----------------------------------------------------------------------------
|
||||
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* Atlanta, Georgia 30332-0415
|
||||
* All Rights Reserved
|
||||
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/* ----------------------------------------------------------------------------
|
||||
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* Atlanta, Georgia 30332-0415
|
||||
* All Rights Reserved
|
||||
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/* ----------------------------------------------------------------------------
|
||||
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* Atlanta, Georgia 30332-0415
|
||||
* All Rights Reserved
|
||||
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
|
||||
|
@ -275,7 +275,7 @@ TEST(Matrix, stream_read ) {
|
|||
-0.3, -8e-2, 5.1, 9.0,
|
||||
1.2, 3.4, 4.5, 6.7).finished();
|
||||
|
||||
string matrixAsString =
|
||||
string matrixAsString =
|
||||
"1.1 2.3 4.2 7.6\n"
|
||||
"-0.3 -8e-2 5.1 9.0\n\r" // Test extra spaces and windows newlines
|
||||
"1.2 \t 3.4 4.5 6.7"; // Test tab as separator
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/* ----------------------------------------------------------------------------
|
||||
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* Atlanta, Georgia 30332-0415
|
||||
* All Rights Reserved
|
||||
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/* ----------------------------------------------------------------------------
|
||||
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* Atlanta, Georgia 30332-0415
|
||||
* All Rights Reserved
|
||||
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/* ----------------------------------------------------------------------------
|
||||
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* Atlanta, Georgia 30332-0415
|
||||
* All Rights Reserved
|
||||
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/* ----------------------------------------------------------------------------
|
||||
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* Atlanta, Georgia 30332-0415
|
||||
* All Rights Reserved
|
||||
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
|
||||
|
|
|
@ -355,7 +355,7 @@ namespace gtsam {
|
|||
NodePtr choose(const L& label, size_t index) const {
|
||||
if (label_ == label)
|
||||
return branches_[index]; // choose branch
|
||||
|
||||
|
||||
// second case, not label of interest, just recurse
|
||||
boost::shared_ptr<Choice> r(new Choice(label_, branches_.size()));
|
||||
for(const NodePtr& branch: branches_)
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/* ----------------------------------------------------------------------------
|
||||
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* Atlanta, Georgia 30332-0415
|
||||
* All Rights Reserved
|
||||
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/* ----------------------------------------------------------------------------
|
||||
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* Atlanta, Georgia 30332-0415
|
||||
* All Rights Reserved
|
||||
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/* ----------------------------------------------------------------------------
|
||||
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* Atlanta, Georgia 30332-0415
|
||||
* All Rights Reserved
|
||||
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
|
||||
|
@ -31,7 +31,7 @@ namespace gtsam {
|
|||
typedef EliminationTree<DiscreteBayesNet, DiscreteFactorGraph> Base; ///< Base class
|
||||
typedef DiscreteEliminationTree This; ///< This class
|
||||
typedef boost::shared_ptr<This> shared_ptr; ///< Shared pointer to this class
|
||||
|
||||
|
||||
/**
|
||||
* Build the elimination tree of a factor graph using pre-computed column structure.
|
||||
* @param factorGraph The factor graph for which to build the elimination tree
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/* ----------------------------------------------------------------------------
|
||||
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* Atlanta, Georgia 30332-0415
|
||||
* All Rights Reserved
|
||||
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/* ----------------------------------------------------------------------------
|
||||
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* Atlanta, Georgia 30332-0415
|
||||
* All Rights Reserved
|
||||
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
|
||||
|
@ -51,7 +51,7 @@ namespace gtsam {
|
|||
typedef JunctionTree<DiscreteBayesTree, DiscreteFactorGraph> Base; ///< Base class
|
||||
typedef DiscreteJunctionTree This; ///< This class
|
||||
typedef boost::shared_ptr<This> shared_ptr; ///< Shared pointer to this class
|
||||
|
||||
|
||||
/**
|
||||
* Build the elimination tree of a factor graph using precomputed column structure.
|
||||
* @param factorGraph The factor graph for which to build the elimination tree
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/* ----------------------------------------------------------------------------
|
||||
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* Atlanta, Georgia 30332-0415
|
||||
* All Rights Reserved
|
||||
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/* ----------------------------------------------------------------------------
|
||||
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* Atlanta, Georgia 30332-0415
|
||||
* All Rights Reserved
|
||||
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/* ----------------------------------------------------------------------------
|
||||
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* Atlanta, Georgia 30332-0415
|
||||
* All Rights Reserved
|
||||
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/* ----------------------------------------------------------------------------
|
||||
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* Atlanta, Georgia 30332-0415
|
||||
* All Rights Reserved
|
||||
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/* ----------------------------------------------------------------------------
|
||||
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* Atlanta, Georgia 30332-0415
|
||||
* All Rights Reserved
|
||||
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/* ----------------------------------------------------------------------------
|
||||
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* Atlanta, Georgia 30332-0415
|
||||
* All Rights Reserved
|
||||
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/* ----------------------------------------------------------------------------
|
||||
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* Atlanta, Georgia 30332-0415
|
||||
* All Rights Reserved
|
||||
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
|
||||
|
|
|
@ -220,7 +220,7 @@ private:
|
|||
& boost::serialization::make_nvp("PinholeBase",
|
||||
boost::serialization::base_object<PinholeBase>(*this));
|
||||
}
|
||||
|
||||
|
||||
public:
|
||||
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
|
||||
};
|
||||
|
|
|
@ -1,12 +1,12 @@
|
|||
/* ----------------------------------------------------------------------------
|
||||
|
||||
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* Atlanta, Georgia 30332-0415
|
||||
* All Rights Reserved
|
||||
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
|
||||
|
||||
|
||||
* See LICENSE for the license information
|
||||
|
||||
|
||||
* -------------------------------------------------------------------------- */
|
||||
|
||||
/**
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/* ----------------------------------------------------------------------------
|
||||
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* Atlanta, Georgia 30332-0415
|
||||
* All Rights Reserved
|
||||
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/* ----------------------------------------------------------------------------
|
||||
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* Atlanta, Georgia 30332-0415
|
||||
* All Rights Reserved
|
||||
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/* ----------------------------------------------------------------------------
|
||||
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* Atlanta, Georgia 30332-0415
|
||||
* All Rights Reserved
|
||||
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/* ----------------------------------------------------------------------------
|
||||
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* Atlanta, Georgia 30332-0415
|
||||
* All Rights Reserved
|
||||
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/* ----------------------------------------------------------------------------
|
||||
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* Atlanta, Georgia 30332-0415
|
||||
* All Rights Reserved
|
||||
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/* ----------------------------------------------------------------------------
|
||||
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* Atlanta, Georgia 30332-0415
|
||||
* All Rights Reserved
|
||||
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/* ----------------------------------------------------------------------------
|
||||
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* Atlanta, Georgia 30332-0415
|
||||
* All Rights Reserved
|
||||
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/* ----------------------------------------------------------------------------
|
||||
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* Atlanta, Georgia 30332-0415
|
||||
* All Rights Reserved
|
||||
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/* ----------------------------------------------------------------------------
|
||||
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* Atlanta, Georgia 30332-0415
|
||||
* All Rights Reserved
|
||||
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/* ----------------------------------------------------------------------------
|
||||
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* Atlanta, Georgia 30332-0415
|
||||
* All Rights Reserved
|
||||
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/* ----------------------------------------------------------------------------
|
||||
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* Atlanta, Georgia 30332-0415
|
||||
* All Rights Reserved
|
||||
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/* ----------------------------------------------------------------------------
|
||||
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* Atlanta, Georgia 30332-0415
|
||||
* All Rights Reserved
|
||||
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/* ----------------------------------------------------------------------------
|
||||
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* Atlanta, Georgia 30332-0415
|
||||
* All Rights Reserved
|
||||
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/* ----------------------------------------------------------------------------
|
||||
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* Atlanta, Georgia 30332-0415
|
||||
* All Rights Reserved
|
||||
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/* ----------------------------------------------------------------------------
|
||||
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* Atlanta, Georgia 30332-0415
|
||||
* All Rights Reserved
|
||||
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/* ----------------------------------------------------------------------------
|
||||
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* Atlanta, Georgia 30332-0415
|
||||
* All Rights Reserved
|
||||
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
|
||||
|
@ -11,7 +11,7 @@
|
|||
|
||||
/**
|
||||
* @file testSerializationGeometry.cpp
|
||||
* @brief
|
||||
* @brief
|
||||
* @author Richard Roberts
|
||||
* @date Feb 7, 2012
|
||||
*/
|
||||
|
|
|
@ -65,7 +65,7 @@ GTSAM_EXPORT Vector4 triangulateHomogeneousDLT(
|
|||
*/
|
||||
GTSAM_EXPORT Point3 triangulateDLT(
|
||||
const std::vector<Matrix34, Eigen::aligned_allocator<Matrix34>>& projection_matrices,
|
||||
const Point2Vector& measurements,
|
||||
const Point2Vector& measurements,
|
||||
double rank_tol = 1e-9);
|
||||
|
||||
/**
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/* ----------------------------------------------------------------------------
|
||||
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* Atlanta, Georgia 30332-0415
|
||||
* All Rights Reserved
|
||||
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
|
||||
|
|
|
@ -65,7 +65,7 @@ namespace gtsam {
|
|||
|
||||
/// @name Standard Interface
|
||||
/// @{
|
||||
|
||||
|
||||
void saveGraph(const std::string &s, const KeyFormatter& keyFormatter = DefaultKeyFormatter) const;
|
||||
};
|
||||
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/* ----------------------------------------------------------------------------
|
||||
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* Atlanta, Georgia 30332-0415
|
||||
* All Rights Reserved
|
||||
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/* ----------------------------------------------------------------------------
|
||||
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* Atlanta, Georgia 30332-0415
|
||||
* All Rights Reserved
|
||||
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/* ----------------------------------------------------------------------------
|
||||
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* Atlanta, Georgia 30332-0415
|
||||
* All Rights Reserved
|
||||
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
|
||||
|
@ -96,7 +96,7 @@ namespace gtsam {
|
|||
|
||||
/** Root cliques */
|
||||
typedef FastVector<sharedClique> Roots;
|
||||
|
||||
|
||||
/** Root cliques */
|
||||
Roots roots_;
|
||||
|
||||
|
@ -190,7 +190,7 @@ namespace gtsam {
|
|||
/// @}
|
||||
/// @name Advanced Interface
|
||||
/// @{
|
||||
|
||||
|
||||
/**
|
||||
* Find parent clique of a conditional. It will look at all parents and
|
||||
* return the one with the lowest index in the ordering.
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/* ----------------------------------------------------------------------------
|
||||
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* Atlanta, Georgia 30332-0415
|
||||
* All Rights Reserved
|
||||
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/* ----------------------------------------------------------------------------
|
||||
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* Atlanta, Georgia 30332-0415
|
||||
* All Rights Reserved
|
||||
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
|
||||
|
@ -75,7 +75,7 @@ namespace gtsam {
|
|||
bool equals(const This& c, double tol = 1e-9) const;
|
||||
|
||||
/// @}
|
||||
|
||||
|
||||
public:
|
||||
/// @name Standard Interface
|
||||
/// @{
|
||||
|
@ -102,10 +102,10 @@ namespace gtsam {
|
|||
|
||||
/** Iterator pointing to first frontal key. */
|
||||
typename FACTOR::const_iterator beginFrontals() const { return asFactor().begin(); }
|
||||
|
||||
|
||||
/** Iterator pointing past the last frontal key. */
|
||||
typename FACTOR::const_iterator endFrontals() const { return asFactor().begin() + nrFrontals_; }
|
||||
|
||||
|
||||
/** Iterator pointing to the first parent key. */
|
||||
typename FACTOR::const_iterator beginParents() const { return endFrontals(); }
|
||||
|
||||
|
|
|
@ -99,7 +99,7 @@ namespace gtsam {
|
|||
|
||||
/** Do sequential elimination of all variables to produce a Bayes net. If an ordering is not
|
||||
* provided, the ordering provided by COLAMD will be used.
|
||||
*
|
||||
*
|
||||
* <b> Example - Full Cholesky elimination in COLAMD order: </b>
|
||||
* \code
|
||||
* boost::shared_ptr<GaussianBayesNet> result = graph.eliminateSequential(EliminateCholesky);
|
||||
|
@ -108,12 +108,12 @@ namespace gtsam {
|
|||
* <b> Example - METIS ordering for elimination
|
||||
* \code
|
||||
* boost::shared_ptr<GaussianBayesNet> result = graph.eliminateSequential(OrderingType::METIS);
|
||||
*
|
||||
*
|
||||
* <b> Example - Full QR elimination in specified order:
|
||||
* \code
|
||||
* boost::shared_ptr<GaussianBayesNet> result = graph.eliminateSequential(EliminateQR, myOrdering);
|
||||
* \endcode
|
||||
*
|
||||
*
|
||||
* <b> Example - Reusing an existing VariableIndex to improve performance, and using COLAMD ordering: </b>
|
||||
* \code
|
||||
* VariableIndex varIndex(graph); // Build variable index
|
||||
|
@ -130,17 +130,17 @@ namespace gtsam {
|
|||
/** Do multifrontal elimination of all variables to produce a Bayes tree. If an ordering is not
|
||||
* provided, the ordering will be computed using either COLAMD or METIS, dependeing on
|
||||
* the parameter orderingType (Ordering::COLAMD or Ordering::METIS)
|
||||
*
|
||||
*
|
||||
* <b> Example - Full Cholesky elimination in COLAMD order: </b>
|
||||
* \code
|
||||
* boost::shared_ptr<GaussianBayesTree> result = graph.eliminateMultifrontal(EliminateCholesky);
|
||||
* \endcode
|
||||
*
|
||||
*
|
||||
* <b> Example - Full QR elimination in specified order:
|
||||
* \code
|
||||
* boost::shared_ptr<GaussianBayesTree> result = graph.eliminateMultifrontal(EliminateQR, myOrdering);
|
||||
* \endcode
|
||||
*
|
||||
*
|
||||
* <b> Example - Reusing an existing VariableIndex to improve performance, and using COLAMD ordering: </b>
|
||||
* \code
|
||||
* VariableIndex varIndex(graph); // Build variable index
|
||||
|
@ -183,7 +183,7 @@ namespace gtsam {
|
|||
const Ordering& ordering,
|
||||
const Eliminate& function = EliminationTraitsType::DefaultEliminate,
|
||||
OptionalVariableIndex variableIndex = boost::none) const;
|
||||
|
||||
|
||||
/** Do multifrontal elimination of the given \c variables in an ordering computed by COLAMD to
|
||||
* 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
|
||||
|
|
Some files were not shown because too many files have changed in this diff Show More
Loading…
Reference in New Issue