simulated2D.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 
23 #include <gtsam/geometry/Point2.h>
24 
25 // \namespace
26 
27 namespace simulated2D {
28 
29  using namespace gtsam;
30 
31  // Simulated2D robots have no orientation, just a position
32 
36  class Values: public gtsam::Values {
37  private:
38  int nrPoses_, nrPoints_;
39 
40  public:
41  typedef gtsam::Values Base;
42  typedef boost::shared_ptr<Point2> sharedPoint;
43 
45  Values() : nrPoses_(0), nrPoints_(0) {
46  }
47 
49  Values(const Base& base) :
50  Base(base), nrPoses_(0), nrPoints_(0) {
51  }
52 
54  void insertPose(Key i, const Point2& p) {
55  insert(i, p);
56  nrPoses_++;
57  }
58 
60  void insertPoint(Key j, const Point2& p) {
61  insert(j, p);
62  nrPoints_++;
63  }
64 
66  int nrPoses() const {
67  return nrPoses_;
68  }
69 
71  int nrPoints() const {
72  return nrPoints_;
73  }
74 
76  Point2 pose(Key i) const {
77  return at<Point2>(i);
78  }
79 
81  Point2 point(Key j) const {
82  return at<Point2>(j);
83  }
84  };
85 
87  inline Point2 prior(const Point2& x) {
88  return x;
89  }
90 
92  inline Point2 prior(const Point2& x, boost::optional<Matrix&> H = boost::none) {
93  if (H) *H = I_2x2;
94  return x;
95  }
96 
98  inline Point2 odo(const Point2& x1, const Point2& x2) {
99  return x2 - x1;
100  }
101 
103  inline Point2 odo(const Point2& x1, const Point2& x2, boost::optional<Matrix&> H1 =
104  boost::none, boost::optional<Matrix&> H2 = boost::none) {
105  if (H1) *H1 = -I_2x2;
106  if (H2) *H2 = I_2x2;
107  return x2 - x1;
108  }
109 
111  inline Point2 mea(const Point2& x, const Point2& l) {
112  return l - x;
113  }
114 
116  inline Point2 mea(const Point2& x, const Point2& l, boost::optional<Matrix&> H1 =
117  boost::none, boost::optional<Matrix&> H2 = boost::none) {
118  if (H1) *H1 = -I_2x2;
119  if (H2) *H2 = I_2x2;
120  return l - x;
121  }
122 
126  template<class VALUE = Point2>
127  class GenericPrior: public NoiseModelFactor1<VALUE> {
128  public:
131  typedef boost::shared_ptr<GenericPrior<VALUE> > shared_ptr;
132  typedef VALUE Pose;
133 
134  Pose measured_;
135 
137  GenericPrior(const Pose& z, const SharedNoiseModel& model, Key key) :
138  Base(model, key), measured_(z) {
139  }
140 
142  Vector evaluateError(const Pose& x, boost::optional<Matrix&> H = boost::none) const override {
143  return (prior(x, H) - measured_);
144  }
145 
146  ~GenericPrior() override {}
147 
150  return boost::static_pointer_cast<gtsam::NonlinearFactor>(
152 
153  private:
154 
157 
159  friend class boost::serialization::access;
160  template<class ARCHIVE>
161  void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
162  ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
163  ar & BOOST_SERIALIZATION_NVP(measured_);
164  }
165  };
166 
170  template<class VALUE = Point2>
171  class GenericOdometry: public NoiseModelFactor2<VALUE, VALUE> {
172  public:
175  typedef boost::shared_ptr<GenericOdometry<VALUE> > shared_ptr;
176  typedef VALUE Pose;
177 
178  Pose measured_;
179 
181  GenericOdometry(const Pose& measured, const SharedNoiseModel& model, Key i1, Key i2) :
182  Base(model, i1, i2), measured_(measured) {
183  }
184 
186  Vector evaluateError(const Pose& x1, const Pose& x2,
187  boost::optional<Matrix&> H1 = boost::none,
188  boost::optional<Matrix&> H2 = boost::none) const override {
189  return (odo(x1, x2, H1, H2) - measured_);
190  }
191 
192  ~GenericOdometry() override {}
193 
196  return boost::static_pointer_cast<gtsam::NonlinearFactor>(
198 
199  private:
200 
203 
205  friend class boost::serialization::access;
206  template<class ARCHIVE>
207  void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
208  ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
209  ar & BOOST_SERIALIZATION_NVP(measured_);
210  }
211  };
212 
216  template<class POSE, class LANDMARK>
217  class GenericMeasurement: public NoiseModelFactor2<POSE, LANDMARK> {
218  public:
221  typedef boost::shared_ptr<GenericMeasurement<POSE, LANDMARK> > shared_ptr;
222  typedef POSE Pose;
223  typedef LANDMARK Landmark;
224 
225  Landmark measured_;
226 
229  Base(model, i, j), measured_(measured) {
230  }
231 
233  Vector evaluateError(const Pose& x1, const Landmark& x2,
234  boost::optional<Matrix&> H1 = boost::none,
235  boost::optional<Matrix&> H2 = boost::none) const override {
236  return (mea(x1, x2, H1, H2) - measured_);
237  }
238 
239  ~GenericMeasurement() override {}
240 
243  return boost::static_pointer_cast<gtsam::NonlinearFactor>(
245 
246  private:
247 
250 
252  friend class boost::serialization::access;
253  template<class ARCHIVE>
254  void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
255  ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
256  ar & BOOST_SERIALIZATION_NVP(measured_);
257  }
258  };
259 
264 
265  // Specialization of a graph for this example domain
266  // TODO: add functions to add factor types
267  class Graph : public NonlinearFactorGraph {
268  public:
269  Graph() {}
270  };
271 
272 } // namespace simulated2D
273 
275 namespace gtsam {
276 template<class POSE, class LANDMARK>
277 struct traits<simulated2D::GenericMeasurement<POSE, LANDMARK> > : Testable<
278  simulated2D::GenericMeasurement<POSE, LANDMARK> > {
279 };
280 
281 template<>
282 struct traits<simulated2D::Values> : public Testable<simulated2D::Values> {
283 };
284 }
285 
boost::shared_ptr< GenericMeasurement< POSE, LANDMARK > > shared_ptr
Definition: simulated2D.h:221
gtsam::NonlinearFactor::shared_ptr clone() const override
Definition: simulated2D.h:242
GenericPrior()
Default constructor.
Definition: simulated2D.h:156
gtsam::NonlinearFactor::shared_ptr clone() const override
Definition: simulated2D.h:149
NoiseModelFactor2< POSE, LANDMARK > Base
base class
Definition: simulated2D.h:219
GenericOdometry()
Default constructor.
Definition: simulated2D.h:202
Factor Graph consisting of non-linear factors.
Point2 prior(const Point2 &x)
Prior on a single pose.
Definition: simulated2D.h:87
noiseModel::Diagonal::shared_ptr model
void insert(Key j, const Value &val)
Definition: Values.cpp:140
Point2 odo(const Point2 &x1, const Point2 &x2)
odometry between two poses
Definition: simulated2D.h:98
Vector2 Point2
Definition: Point2.h:27
Pose measured_
prior mean
Definition: simulated2D.h:134
VALUE Pose
shortcut to Pose type
Definition: simulated2D.h:176
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
GenericOdometry< VALUE > This
Definition: simulated2D.h:174
NoiseModelFactor2< VALUE, VALUE > Base
base class
Definition: simulated2D.h:173
Vector evaluateError(const Pose &x, boost::optional< Matrix & > H=boost::none) const override
Return error and optional derivative.
Definition: simulated2D.h:142
Point2 point(Key j) const
Return point j.
Definition: simulated2D.h:81
GenericOdometry(const Pose &measured, const SharedNoiseModel &model, Key i1, Key i2)
Create odometry.
Definition: simulated2D.h:181
void serialize(ARCHIVE &ar, const unsigned int)
Definition: simulated2D.h:207
NoiseModelFactor1< VALUE > Base
base class
Definition: simulated2D.h:129
GenericPrior< VALUE > This
Definition: simulated2D.h:130
static const Line3 l(Rot3(), 1, 1)
Eigen::VectorXd Vector
Definition: Vector.h:38
void insertPose(Key i, const Point2 &p)
Insert a pose.
Definition: simulated2D.h:54
GenericMeasurement(const Landmark &measured, const SharedNoiseModel &model, Key i, Key j)
Create measurement factor.
Definition: simulated2D.h:228
Vector evaluateError(const Pose &x1, const Landmark &x2, boost::optional< Matrix & > H1=boost::none, boost::optional< Matrix & > H2=boost::none) const override
Evaluate error and optionally return derivatives.
Definition: simulated2D.h:233
GenericMeasurement< Point2, Point2 > Measurement
Definition: simulated2D.h:263
Point2 pose(Key i) const
Return pose i.
Definition: simulated2D.h:76
Vector evaluateError(const Pose &x1, const Pose &x2, boost::optional< Matrix & > H1=boost::none, boost::optional< Matrix & > H2=boost::none) const override
Evaluate error and optionally return derivatives.
Definition: simulated2D.h:186
Pose measured_
odometry measurement
Definition: simulated2D.h:178
boost::shared_ptr< This > shared_ptr
gtsam::NonlinearFactor::shared_ptr clone() const override
Definition: simulated2D.h:195
void insertPoint(Key j, const Point2 &p)
Insert a point.
Definition: simulated2D.h:60
Values()
Constructor.
Definition: simulated2D.h:45
#define This
int nrPoses() const
Number of poses.
Definition: simulated2D.h:66
traits
Definition: chartTesting.h:28
GenericPrior(const Pose &z, const SharedNoiseModel &model, Key key)
Create generic prior.
Definition: simulated2D.h:137
GenericPrior< Point2 > Prior
Definition: simulated2D.h:261
Values(const Base &base)
Copy constructor.
Definition: simulated2D.h:49
void serialize(ARCHIVE &ar, const unsigned int)
Definition: simulated2D.h:254
void serialize(ARCHIVE &ar, const unsigned int)
Definition: simulated2D.h:161
Non-linear factor base classes.
GenericOdometry< Point2 > Odometry
Definition: simulated2D.h:262
boost::shared_ptr< Point2 > sharedPoint
shortcut to shared Point type
Definition: simulated2D.h:42
Pose3 x1
Definition: testPose3.cpp:588
Landmark measured_
Measurement.
Definition: simulated2D.h:225
float * p
GenericMeasurement()
Default constructor.
Definition: simulated2D.h:249
boost::shared_ptr< GenericOdometry< VALUE > > shared_ptr
Definition: simulated2D.h:175
GenericMeasurement< POSE, LANDMARK > This
Definition: simulated2D.h:220
POSE Pose
shortcut to Pose type
Definition: simulated2D.h:222
Annotation indicating that a class derives from another given type.
Definition: attr.h:42
VALUE Pose
shortcut to Pose type
Definition: simulated2D.h:132
boost::shared_ptr< GenericPrior< VALUE > > shared_ptr
Definition: simulated2D.h:131
Point3 measured
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
2D Point
LANDMARK Landmark
shortcut to Landmark type
Definition: simulated2D.h:223
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:61
std::ptrdiff_t j
Point2 mea(const Point2 &x, const Point2 &l)
measurement between landmark and pose
Definition: simulated2D.h:111
noiseModel::Base::shared_ptr SharedNoiseModel
Definition: NoiseModel.h:734
int nrPoints() const
Number of points.
Definition: simulated2D.h:71
gtsam::Values Base
base class
Definition: simulated2D.h:41


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:44:10