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
gtsam::LieGroup::between
Class between(const Class &g) const
Definition: Lie.h:52
H
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
Definition: gnuplot_common_settings.hh:74
gtsam::NonlinearFactor::shared_ptr
std::shared_ptr< This > shared_ptr
Definition: NonlinearFactor.h:78
Pose2.h
2D Pose
pose
static const Pose3 pose(Rot3(Vector3(1, -1, -1).asDiagonal()), Point3(0, 0, 0.5))
simulated2DOriented::GenericOdometry
Definition: simulated2DOriented.h:105
simulated2DOriented::GenericOdometry::~GenericOdometry
~GenericOdometry() override
Definition: simulated2DOriented.h:121
simulated2DOriented::GenericOdometry::clone
gtsam::NonlinearFactor::shared_ptr clone() const override
Definition: simulated2DOriented.h:130
simulated2DOriented::GenericPosePrior
Unary factor encoding a soft prior on a vector.
Definition: simulated2DOriented.h:84
x
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
Definition: gnuplot_common_settings.hh:12
simulated2DOriented::Graph::Graph
Graph()
Definition: simulated2DOriented.h:141
simulated2DOriented::GenericPosePrior::evaluateError
Vector evaluateError(const Pose2 &x, OptionalMatrixType H=OptionalNone) const
Evaluate error and optionally derivative.
Definition: simulated2DOriented.h:94
measured
Point2 measured(-17, 30)
simulated2DOriented::GenericOdometry::measured_
Pose2 measured_
Between measurement for odometry factor.
Definition: simulated2DOriented.h:106
gtsam::Vector
Eigen::VectorXd Vector
Definition: Vector.h:38
simulated2DOriented
Definition: simulated2DOriented.h:28
Eigen::internal::VALUE
@ VALUE
Definition: SpecialFunctionsImpl.h:729
gtsam_unstable.tests.test_ProjectionFactorRollingShutter.point
point
Definition: test_ProjectionFactorRollingShutter.py:25
simulated2DOriented::Values::Values
Values()
Definition: simulated2DOriented.h:37
j
std::ptrdiff_t j
Definition: tut_arithmetic_redux_minmax.cpp:2
simulated2DOriented::GenericPosePrior::GenericPosePrior
GenericPosePrior(const Pose2 &measured, const SharedNoiseModel &model, Key key)
Create generic pose prior.
Definition: simulated2DOriented.h:89
OptionalNone
#define OptionalNone
Definition: NonlinearFactor.h:49
x1
Pose3 x1
Definition: testPose3.cpp:663
simulated2DOriented::odo
Pose2 odo(const Pose2 &x1, const Pose2 &x2)
odometry between two poses
Definition: simulated2DOriented.h:72
gtsam::NonlinearFactorGraph
Definition: NonlinearFactorGraph.h:55
gtsam::NoiseModelFactorN
Definition: NonlinearFactor.h:431
OptionalJacobian.h
Special class for optional Jacobian arguments.
gtsam::Point2
Vector2 Point2
Definition: Point2.h:32
gtsam::SharedNoiseModel
noiseModel::Base::shared_ptr SharedNoiseModel
Definition: NoiseModel.h:762
simulated2DOriented::GenericOdometry::GenericOdometry
GenericOdometry(const Pose2 &measured, const SharedNoiseModel &model, Key i1, Key i2)
Definition: simulated2DOriented.h:116
gtsam::LieGroup::localCoordinates
TangentVector localCoordinates(const Class &g) const
localCoordinates as required by manifold concept: finds tangent vector between *this and g
Definition: Lie.h:136
model
noiseModel::Diagonal::shared_ptr model
Definition: doc/Code/Pose2SLAMExample.cpp:7
key
const gtsam::Symbol key('X', 0)
NonlinearFactor.h
Non-linear factor base classes.
simulated2DOriented::GenericOdometry::This
GenericOdometry< VALUE > This
Definition: simulated2DOriented.h:108
gtsam
traits
Definition: SFMdata.h:40
i1
double i1(double x)
Definition: i1.c:150
gtsam::OptionalJacobian
Definition: OptionalJacobian.h:38
NonlinearFactorGraph.h
Factor Graph consisting of non-linear factors.
gtsam::Values
Definition: Values.h:65
simulated2DOriented::Odometry
GenericOdometry< Pose2 > Odometry
Definition: simulated2DOriented.h:136
p
float * p
Definition: Tutorial_Map_using.cpp:9
gtsam::Values::insert
void insert(Key j, const Value &val)
Definition: Values.cpp:155
This
#define This
Definition: ActiveSetSolver-inl.h:27
simulated2DOriented::Values::insertPose
void insertPose(Key i, const Pose2 &p)
insert a pose
Definition: simulated2DOriented.h:40
simulated2DOriented::GenericOdometry::evaluateError
Vector evaluateError(const VALUE &x1, const VALUE &x2, OptionalMatrixType H1, OptionalMatrixType H2) const override
Evaluate error and optionally derivative.
Definition: simulated2DOriented.h:124
gtsam::OptionalMatrixType
Matrix * OptionalMatrixType
Definition: NonlinearFactor.h:55
simulated2DOriented::Values::nrPoses_
int nrPoses_
Definition: simulated2DOriented.h:35
simulated2DOriented::GenericPosePrior::measured_
Pose2 measured_
measurement
Definition: simulated2DOriented.h:86
gtsam::Key
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:97
simulated2DOriented::Graph
Graph specialization for syntactic sugar use with matlab.
Definition: simulated2DOriented.h:139
simulated2DOriented::prior
Pose2 prior(const Pose2 &x)
Prior on a single pose.
Definition: simulated2DOriented.h:61
x2
Pose3 x2(Rot3::Ypr(0.0, 0.0, 0.0), l2)
i
int i
Definition: BiCGSTAB_step_by_step.cpp:9
Values.h
A non-templated config holding any types of Manifold-group elements.
gtsam::Pose2
Definition: Pose2.h:39
simulated2DOriented::Values::insertPoint
void insertPoint(Key j, const Point2 &p)
insert a landmark
Definition: simulated2DOriented.h:46


gtsam
Author(s):
autogenerated on Sat Nov 16 2024 04:04:19