33 namespace equality_constraints {
46 namespace inequality_constraints {
53 template<
class VALUE,
unsigned int IDX>
57 typedef boost::shared_ptr<ScalarCoordConstraint1<VALUE, IDX> >
shared_ptr;
75 bool isGreaterThan,
double mu = 1000.0) :
76 Base(key, c, isGreaterThan,
mu) {
83 inline unsigned int index()
const {
return IDX; }
90 double value(
const Point&
x, boost::optional<Matrix&>
H =
91 boost::none)
const override {
113 template<
class T1,
class T2>
122 template<
class VALUE>
143 Base(key1, key2, range_bound, false,
mu) {}
154 boost::optional<Matrix&> H1 = boost::none,
155 boost::optional<Matrix&> H2 = boost::none)
const override {
170 template<
class POSE,
class POINT>
192 double range_bound,
double mu = 1000.0)
193 : Base(key1, key2, range_bound, true,
mu) {}
204 boost::optional<Matrix&> H1 = boost::none,
205 boost::optional<Matrix&> H2 = boost::none)
const override {
ScalarCoordConstraint1< Point2, 1 > PoseYInequality
Simulated2D domain example factor constraining Y.
NonlinearEquality1< Point2 > UnaryEqualityConstraint
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)
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
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.
const Symbol key1('v', 1)
~ScalarCoordConstraint1() override
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
VALUE Point
Constrained variable type.
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.)
POSE Pose
Type of pose variable constrained.
~MaxDistanceConstraint() override
unsigned int index() const
~MinDistanceConstraint() override
POINT Point
Type of point variable constrained.
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.
const Symbol key2('v', 2)
VALUE Point
Type of variable constrained.
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.