simulated2DOriented.h
Go to the documentation of this file.
1 /* ----------------------------------------------------------------------------
2 
3  * GTSAM Copyright 2010, Georgia Tech Research Corporation,
4  * Atlanta, Georgia 30332-0415
5  * All Rights Reserved
6  * Authors: Frank Dellaert, et al. (see THANKS for the full author list)
7 
8  * See LICENSE for the license information
9 
10  * -------------------------------------------------------------------------- */
11 
18 // \callgraph
19 #pragma once
20 
21 #include <gtsam/geometry/Pose2.h>
22 #include <gtsam/nonlinear/Values.h>
26 
27 // \namespace
29 
30  using namespace gtsam;
31 
34  class Values: public gtsam::Values {
35  int nrPoses_, nrPoints_;
36  public:
37  Values() : nrPoses_(0), nrPoints_(0) {}
38 
40  void insertPose(Key i, const Pose2& p) {
41  insert(i, p);
42  nrPoses_++;
43  }
44 
46  void insertPoint(Key j, const Point2& p) {
47  insert(j, p);
48  nrPoints_++;
49  }
50 
51  int nrPoses() const { return nrPoses_; }
52  int nrPoints() const { return nrPoints_; }
53 
54  Pose2 pose(Key i) const { return at<Pose2>(i); }
55  Point2 point(Key j) const { return at<Point2>(j); }
56  };
57 
58  //TODO:: point prior is not implemented right now
59 
61  inline Pose2 prior(const Pose2& x) {
62  return x;
63  }
64 
67  if (H) *H = I_3x3;
68  return x;
69  }
70 
72  inline Pose2 odo(const Pose2& x1, const Pose2& x2) {
73  return x1.between(x2);
74  }
75 
79  return x1.between(x2, H1, H2);
80  }
81 
83  template<class VALUE = Pose2>
84  struct GenericPosePrior: public NoiseModelFactorN<VALUE> {
85 
87 
90  NoiseModelFactorN<VALUE>(model, key), measured_(measured) {
91  }
92 
95  OptionalNone) const {
96  return measured_.localCoordinates(prior(x, H));
97  }
98 
99  };
100 
104  template<class VALUE = Pose2>
105  struct GenericOdometry: public NoiseModelFactorN<VALUE, VALUE> {
107 
109 
110  // Provide access to the Matrix& version of evaluateError:
111  using NoiseModelFactor2<VALUE, VALUE>::evaluateError;
112 
117  Key i1, Key i2) :
118  NoiseModelFactorN<VALUE, VALUE>(model, i1, i2), measured_(measured) {
119  }
120 
121  ~GenericOdometry() override {}
122 
125  OptionalMatrixType H1, OptionalMatrixType H2) const override {
126  return measured_.localCoordinates(odo(x1, x2, H1, H2));
127  }
128 
131  return std::static_pointer_cast<gtsam::NonlinearFactor>(
133 
134  };
135 
137 
139  class Graph : public NonlinearFactorGraph {
140  public:
141  Graph() {}
142  // TODO: add functions to add factors
143  };
144 
145 } // namespace simulated2DOriented
const gtsam::Symbol key('X', 0)
Point2 measured(-17, 30)
Unary factor encoding a soft prior on a vector.
Pose2 pose(Key i) const
get a pose
A non-templated config holding any types of Manifold-group elements.
Factor Graph consisting of non-linear factors.
void insertPoint(Key j, const Point2 &p)
insert a landmark
noiseModel::Diagonal::shared_ptr model
Vector2 Point2
Definition: Point2.h:32
Pose3 x2(Rot3::Ypr(0.0, 0.0, 0.0), l2)
set noclip points set clip one set noclip two set bar set border lt lw set xdata set ydata set zdata set x2data set y2data set boxwidth set dummy y set format x g set format y g set format x2 g set format y2 g set format z g set angles radians set nogrid set key title set key left top Right noreverse box linetype linewidth samplen spacing width set nolabel set noarrow set nologscale set logscale x set set pointsize set encoding default set nopolar set noparametric set set set set surface set nocontour set clabel set mapping cartesian set nohidden3d set cntrparam order set cntrparam linear set cntrparam levels auto set cntrparam points set size set set xzeroaxis lt lw set x2zeroaxis lt lw set yzeroaxis lt lw set y2zeroaxis lt lw set tics in set ticslevel set tics set mxtics default set mytics default set mx2tics default set my2tics default set xtics border mirror norotate autofreq set ytics border mirror norotate autofreq set ztics border nomirror norotate autofreq set nox2tics set noy2tics set timestamp bottom norotate set rrange [*:*] noreverse nowriteback set trange [*:*] noreverse nowriteback set urange [*:*] noreverse nowriteback set vrange [*:*] noreverse nowriteback set xlabel matrix size set x2label set timefmt d m y n H
#define OptionalNone
TangentVector localCoordinates(const Class &g) const
localCoordinates as required by manifold concept: finds tangent vector between *this and g ...
Definition: Lie.h:136
GenericPosePrior(const Pose2 &measured, const SharedNoiseModel &model, Key key)
Create generic pose prior.
Graph specialization for syntactic sugar use with matlab.
Matrix * OptionalMatrixType
int nrPoints() const
nr of landmarks
Eigen::VectorXd Vector
Definition: Vector.h:38
Point2 point(Key j) const
get a landmark
Pose2 odo(const Pose2 &x1, const Pose2 &x2)
odometry between two poses
int nrPoses() const
nr of poses
Pose2 measured_
Between measurement for odometry factor.
gtsam::NonlinearFactor::shared_ptr clone() const override
#define This
void insertPose(Key i, const Pose2 &p)
insert a pose
traits
Definition: chartTesting.h:28
Non-linear factor base classes.
Class between(const Class &g) const
Definition: Lie.h:52
Pose3 x1
Definition: testPose3.cpp:663
std::shared_ptr< This > shared_ptr
float * p
GenericOdometry(const Pose2 &measured, const SharedNoiseModel &model, Key i1, Key i2)
GenericOdometry< Pose2 > Odometry
void insert(Key j, const Value &val)
Definition: Values.cpp:155
Special class for optional Jacobian arguments.
Vector evaluateError(const Pose2 &x, OptionalMatrixType H=OptionalNone) const
Evaluate error and optionally derivative.
2D Pose
set noclip points set clip one set noclip two set bar set border lt lw set xdata set ydata set zdata set x2data set y2data set boxwidth set dummy x
Vector evaluateError(const VALUE &x1, const VALUE &x2, OptionalMatrixType H1, OptionalMatrixType H2) const override
Evaluate error and optionally derivative.
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:102
std::ptrdiff_t j
noiseModel::Base::shared_ptr SharedNoiseModel
Definition: NoiseModel.h:741
Pose2 prior(const Pose2 &x)
Prior on a single pose.


gtsam
Author(s):
autogenerated on Tue Jul 4 2023 02:35:49