simulated2DConstraints.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 
20 #pragma once
21 
23 
27 #include <tests/simulated2D.h>
28 
29 // \namespace
30 
31 namespace simulated2D {
32 
33  namespace equality_constraints {
34 
39 
43 
44  } // \namespace equality_constraints
45 
46  namespace inequality_constraints {
47 
53  template<class VALUE, unsigned int IDX>
57  typedef boost::shared_ptr<ScalarCoordConstraint1<VALUE, IDX> > shared_ptr;
58  typedef VALUE Point;
59 
61 
64  return boost::static_pointer_cast<gtsam::NonlinearFactor>(
66 
75  bool isGreaterThan, double mu = 1000.0) :
76  Base(key, c, isGreaterThan, mu) {
77  }
78 
83  inline unsigned int index() const { return IDX; }
84 
90  double value(const Point& x, boost::optional<Matrix&> H =
91  boost::none) const override {
92  if (H) {
93  Matrix D = Matrix::Zero(1, traits<Point>::GetDimension(x));
94  D(0, IDX) = 1.0;
95  *H = D;
96  }
97  return traits<Point>::Logmap(x)(IDX);
98  }
99  };
100 
104 
113  template<class T1, class T2>
114  double range_trait(const T1& a, const T2& b) { return distance2(a, b); }
115 
122  template<class VALUE>
123  struct MaxDistanceConstraint : public BoundingConstraint2<VALUE, VALUE> {
126  typedef VALUE Point;
127 
129 
132  return boost::static_pointer_cast<gtsam::NonlinearFactor>(
134 
142  MaxDistanceConstraint(Key key1, Key key2, double range_bound, double mu = 1000.0) :
143  Base(key1, key2, range_bound, false, mu) {}
144 
153  double value(const Point& x1, const Point& x2,
154  boost::optional<Matrix&> H1 = boost::none,
155  boost::optional<Matrix&> H2 = boost::none) const override {
156  if (H1) *H1 = numericalDerivative21(range_trait<Point,Point>, x1, x2, 1e-5);
157  if (H1) *H2 = numericalDerivative22(range_trait<Point,Point>, x1, x2, 1e-5);
158  return range_trait(x1, x2);
159  }
160  };
161 
163 
170  template<class POSE, class POINT>
171  struct MinDistanceConstraint : public BoundingConstraint2<POSE, POINT> {
174  typedef POSE Pose;
175  typedef POINT Point;
176 
178 
181  return boost::static_pointer_cast<gtsam::NonlinearFactor>(
183 
192  double range_bound, double mu = 1000.0)
193  : Base(key1, key2, range_bound, true, mu) {}
194 
203  double value(const Pose& x1, const Point& x2,
204  boost::optional<Matrix&> H1 = boost::none,
205  boost::optional<Matrix&> H2 = boost::none) const override {
206  if (H1) *H1 = numericalDerivative21(range_trait<Pose,Point>, x1, x2, 1e-5);
207  if (H1) *H2 = numericalDerivative22(range_trait<Pose,Point>, x1, x2, 1e-5);
208  return range_trait(x1, x2);
209  }
210  };
211 
213 
214 
215  } // \namespace inequality_constraints
216 
217 } // \namespace simulated2D
218 
ScalarCoordConstraint1< Point2, 1 > PoseYInequality
Simulated2D domain example factor constraining Y.
NonlinearEquality1< Point2 > UnaryEqualityConstraint
Scalar * b
Definition: benchVecAdd.cpp:17
NonlinearEquality1< Point2 > UnaryEqualityPointConstraint
MaxDistanceConstraint(Key key1, Key key2, double range_bound, double mu=1000.0)
ScalarCoordConstraint1(Key key, double c, bool isGreaterThan, double mu=1000.0)
double mu
Provides partially implemented constraints to implement bounds.
double distance2(const Point2 &p, const Point2 &q, OptionalJacobian< 1, 2 > H1, OptionalJacobian< 1, 2 > H2)
distance between two points
Definition: Point2.cpp:39
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:43
Scalar Scalar * c
Definition: benchVecAdd.cpp:17
Pose2 T2(M_PI/2.0, Point2(0.0, 2.0))
Some functions to compute numerical derivatives.
Pose3 x2(Rot3::Ypr(0.0, 0.0, 0.0), l2)
internal::FixedSizeMatrix< Y, X1 >::type numericalDerivative21(const boost::function< Y(const X1 &, const X2 &)> &h, const X1 &x1, const X2 &x2, double delta=1e-5)
NonlinearEquality2< Point2 > PoseEqualityConstraint
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
BoundingConstraint2< POSE, POINT > Base
Base class for factor.
Array33i a
const Symbol key1('v', 1)
BoundingConstraint1< VALUE > Base
Base class convenience typedef.
internal::FixedSizeMatrix< Y, X2 >::type numericalDerivative22(boost::function< Y(const X1 &, const X2 &)> h, const X1 &x1, const X2 &x2, double delta=1e-5)
gtsam::NonlinearFactor::shared_ptr clone() const override
BetweenConstraint< Point2 > OdoEqualityConstraint
NonlinearEquality2< Point2 > PointEqualityConstraint
MaxDistanceConstraint< VALUE > This
This class for factor.
boost::shared_ptr< This > shared_ptr
double value(const Point &x1, const Point &x2, boost::optional< Matrix & > H1=boost::none, boost::optional< Matrix & > H2=boost::none) const override
Array< double, 1, 3 > e(1./3., 0.5, 2.)
#define This
boost::shared_ptr< ScalarCoordConstraint1< VALUE, IDX > > shared_ptr
boost::shared_ptr convenience typedef
double range_trait(const T1 &a, const T2 &b)
MinDistanceConstraint(Key key1, Key key2, double range_bound, double mu=1000.0)
double value(const Point &x, boost::optional< Matrix & > H=boost::none) const override
gtsam::NonlinearFactor::shared_ptr clone() const override
measurement functions and derivatives for simulated 2D robot
BoundingConstraint2< VALUE, VALUE > Base
Base class for factor.
MinDistanceConstraint< POSE, POINT > This
This class for factor.
Pose3 x1
Definition: testPose3.cpp:588
const Symbol key2('v', 2)
double value(const Pose &x1, const Point &x2, boost::optional< Matrix & > H1=boost::none, boost::optional< Matrix & > H2=boost::none) const override
ScalarCoordConstraint1< VALUE, IDX > This
This class convenience typedef.
Pose2 T1(M_PI/4.0, Point2(sqrt(0.5), sqrt(0.5)))
MinDistanceConstraint< Point2, Point2 > LandmarkAvoid
Simulated2D domain example factor.
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
ScalarCoordConstraint1< Point2, 0 > PoseXInequality
Simulated2D domain example factor constraining X.
gtsam::NonlinearFactor::shared_ptr clone() const override
MaxDistanceConstraint< Point2 > PoseMaxDistConstraint
Simulated2D domain example factor.
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:61


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