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>
25 
26 // \namespace
28 
29  using namespace gtsam;
30 
33  class Values: public gtsam::Values {
34  int nrPoses_, nrPoints_;
35  public:
36  Values() : nrPoses_(0), nrPoints_(0) {}
37 
39  void insertPose(Key i, const Pose2& p) {
40  insert(i, p);
41  nrPoses_++;
42  }
43 
45  void insertPoint(Key j, const Point2& p) {
46  insert(j, p);
47  nrPoints_++;
48  }
49 
50  int nrPoses() const { return nrPoses_; }
51  int nrPoints() const { return nrPoints_; }
52 
53  Pose2 pose(Key i) const { return at<Pose2>(i); }
54  Point2 point(Key j) const { return at<Point2>(j); }
55  };
56 
57  //TODO:: point prior is not implemented right now
58 
60  inline Pose2 prior(const Pose2& x) {
61  return x;
62  }
63 
65  Pose2 prior(const Pose2& x, boost::optional<Matrix&> H = boost::none) {
66  if (H) *H = I_3x3;
67  return x;
68  }
69 
71  inline Pose2 odo(const Pose2& x1, const Pose2& x2) {
72  return x1.between(x2);
73  }
74 
76  Pose2 odo(const Pose2& x1, const Pose2& x2, boost::optional<Matrix&> H1 =
77  boost::none, boost::optional<Matrix&> H2 = boost::none) {
78  return x1.between(x2, H1, H2);
79  }
80 
82  template<class VALUE = Pose2>
83  struct GenericPosePrior: public NoiseModelFactor1<VALUE> {
84 
86 
89  NoiseModelFactor1<VALUE>(model, key), measured_(measured) {
90  }
91 
93  Vector evaluateError(const Pose2& x, boost::optional<Matrix&> H =
94  boost::none) const {
95  return measured_.localCoordinates(prior(x, H));
96  }
97 
98  };
99 
103  template<class VALUE = Pose2>
104  struct GenericOdometry: public NoiseModelFactor2<VALUE, VALUE> {
106 
108 
113  Key i1, Key i2) :
114  NoiseModelFactor2<VALUE, VALUE>(model, i1, i2), measured_(measured) {
115  }
116 
117  ~GenericOdometry() override {}
118 
120  Vector evaluateError(const VALUE& x1, const VALUE& x2,
121  boost::optional<Matrix&> H1 = boost::none,
122  boost::optional<Matrix&> H2 = boost::none) const override {
123  return measured_.localCoordinates(odo(x1, x2, H1, H2));
124  }
125 
128  return boost::static_pointer_cast<gtsam::NonlinearFactor>(
130 
131  };
132 
134 
136  class Graph : public NonlinearFactorGraph {
137  public:
138  Graph() {}
139  // TODO: add functions to add factors
140  };
141 
142 } // namespace simulated2DOriented
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
void insert(Key j, const Value &val)
Definition: Values.cpp:140
Vector2 Point2
Definition: Point2.h:27
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
GenericPosePrior(const Pose2 &measured, const SharedNoiseModel &model, Key key)
Create generic pose prior.
Graph specialization for syntactic sugar use with matlab.
Eigen::VectorXd Vector
Definition: Vector.h:38
Pose2 odo(const Pose2 &x1, const Pose2 &x2)
odometry between two poses
boost::shared_ptr< This > shared_ptr
Point2 point(Key j) const
get a landmark
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
Vector evaluateError(const VALUE &x1, const VALUE &x2, boost::optional< Matrix & > H1=boost::none, boost::optional< Matrix & > H2=boost::none) const override
Evaluate error and optionally derivative.
traits
Definition: chartTesting.h:28
int nrPoints() const
nr of landmarks
Non-linear factor base classes.
int nrPoses() const
nr of poses
Pose3 x1
Definition: testPose3.cpp:588
float * p
Class between(const Class &g) const
Definition: Lie.h:51
GenericOdometry(const Pose2 &measured, const SharedNoiseModel &model, Key i1, Key i2)
GenericOdometry< Pose2 > Odometry
Vector evaluateError(const Pose2 &x, boost::optional< Matrix & > H=boost::none) const
Evaluate error and optionally derivative.
2D Pose
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
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:61
std::ptrdiff_t j
noiseModel::Base::shared_ptr SharedNoiseModel
Definition: NoiseModel.h:734
Pose2 prior(const Pose2 &x)
Prior on a single pose.
TangentVector localCoordinates(const Class &g) const
localCoordinates as required by manifold concept: finds tangent vector between *this and g ...
Definition: Lie.h:135


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