Skip to content

Commit

Permalink
Merge pull request #1139 from borglab/fix/doc
Browse files Browse the repository at this point in the history
  • Loading branch information
dellaert authored Mar 25, 2022
2 parents 239a978 + 476eb9c commit 134a6b8
Show file tree
Hide file tree
Showing 9 changed files with 255 additions and 89 deletions.
8 changes: 4 additions & 4 deletions doc/Code/LocalizationExample2.cpp
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
// add unary measurement factors, like GPS, on all three poses
noiseModel::Diagonal::shared_ptr unaryNoise =
auto 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));
graph.add(boost::make_shared<UnaryFactor>(3, 4.0, 0.0, unaryNoise));
graph.emplace_shared<UnaryFactor>(1, 0.0, 0.0, unaryNoise);
graph.emplace_shared<UnaryFactor>(2, 2.0, 0.0, unaryNoise);
graph.emplace_shared<UnaryFactor>(3, 4.0, 0.0, unaryNoise);

7 changes: 3 additions & 4 deletions doc/Code/LocalizationFactor.cpp
Original file line number Diff line number Diff line change
@@ -1,13 +1,12 @@
class UnaryFactor: public NoiseModelFactor1<Pose2> {
double mx_, my_; ///< X and Y measurements

public:
UnaryFactor(Key j, double x, double y, const SharedNoiseModel& model):
NoiseModelFactor1<Pose2>(model, j), mx_(x), my_(y) {}

Vector evaluateError(const Pose2& q,
boost::optional<Matrix&> H = boost::none) const
{
Vector evaluateError(const Pose2& q,
boost::optional<Matrix&> H = boost::none) const override {
const Rot2& R = q.rotation();
if (H) (*H) = (gtsam::Matrix(2, 3) <<
R.c(), -R.s(), 0.0,
Expand Down
8 changes: 3 additions & 5 deletions doc/Code/OdometryExample.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -3,13 +3,11 @@ 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::Sigmas(Vector3(0.3, 0.3, 0.1));
graph.addPrior(1, priorMean, priorNoise);
auto 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::Sigmas(Vector3(0.2, 0.2, 0.1));
auto 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));
17 changes: 10 additions & 7 deletions doc/Code/OdometryOutput1.txt
Original file line number Diff line number Diff line change
@@ -1,11 +1,14 @@
Factor Graph:
size: 3
factor 0: PriorFactor on 1
prior mean: (0, 0, 0)

Factor 0: PriorFactor on 1
prior mean: (0, 0, 0)
noise model: diagonal sigmas [0.3; 0.3; 0.1];
factor 1: BetweenFactor(1,2)
measured: (2, 0, 0)
noise model: diagonal sigmas [0.2; 0.2; 0.1];
factor 2: BetweenFactor(2,3)
measured: (2, 0, 0)

Factor 1: BetweenFactor(1,2)
measured: (2, 0, 0)
noise model: diagonal sigmas [0.2; 0.2; 0.1];

Factor 2: BetweenFactor(2,3)
measured: (2, 0, 0)
noise model: diagonal sigmas [0.2; 0.2; 0.1];
24 changes: 18 additions & 6 deletions doc/Code/OdometryOutput2.txt
Original file line number Diff line number Diff line change
@@ -1,11 +1,23 @@
Initial Estimate:

Values with 3 values:
Value 1: (0.5, 0, 0.2)
Value 2: (2.3, 0.1, -0.2)
Value 3: (4.1, 0.1, 0.1)
Value 1: (gtsam::Pose2)
(0.5, 0, 0.2)

Value 2: (gtsam::Pose2)
(2.3, 0.1, -0.2)

Value 3: (gtsam::Pose2)
(4.1, 0.1, 0.1)

Final Result:

Values with 3 values:
Value 1: (-1.8e-16, 8.7e-18, -9.1e-19)
Value 2: (2, 7.4e-18, -2.5e-18)
Value 3: (4, -1.8e-18, -3.1e-18)
Value 1: (gtsam::Pose2)
(7.5-16, -5.3-16, -1.8-16)

Value 2: (gtsam::Pose2)
(2, -1.1-15, -2.5-16)

Value 3: (gtsam::Pose2)
(4, -1.7-15, -2.5-16)
18 changes: 9 additions & 9 deletions doc/Code/OdometryOutput3.txt
Original file line number Diff line number Diff line change
@@ -1,12 +1,12 @@
x1 covariance:
0.09 1.1e-47 5.7e-33
1.1e-47 0.09 1.9e-17
5.7e-33 1.9e-17 0.01
0.09 1.7e-33 2.8e-33
1.7e-33 0.09 2.6e-17
2.8e-33 2.6e-17 0.01
x2 covariance:
0.13 4.7e-18 2.4e-18
4.7e-18 0.17 0.02
2.4e-18 0.02 0.02
0.13 1.2e-18 6.1e-19
1.2e-18 0.17 0.02
6.1e-19 0.02 0.02
x3 covariance:
0.17 2.7e-17 8.4e-18
2.7e-17 0.37 0.06
8.4e-18 0.06 0.03
0.17 8.6e-18 2.7e-18
8.6e-18 0.37 0.06
2.7e-18 0.06 0.03
Loading

0 comments on commit 134a6b8

Please sign in to comment.