Go to the documentation of this file.
87 std::placeholders::_1, std::placeholders::_2, 1
e-9)) :
98 std::placeholders::_1, std::placeholders::_2, 1
e-9)) :
105 return keys().front();
114 std::cout << (
s.empty() ?
s :
s +
" ") <<
"Constraint: on ["
115 << keyFormatter(this->
key()) <<
"]\n";
123 const This*
e =
dynamic_cast<const This*
>(&
f);
134 const T& xj =
c.at<
T>(this->
key());
148 *
H = Matrix::Identity(nj,nj);
152 *
H = Matrix::Identity(nj,nj);
153 return Vector::Zero(nj);
156 throw std::invalid_argument(
157 "Linearization point not feasible for "
159 return Vector::Constant(nj, std::numeric_limits<double>::infinity());
174 const T& xj =
x.at<
T>(this->
key());
184 return std::static_pointer_cast<gtsam::NonlinearFactor>(
194 #if GTSAM_ENABLE_BOOST_SERIALIZATION
195 friend class boost::serialization::access;
197 template<
class ARCHIVE>
198 void serialize(ARCHIVE & ar,
const unsigned int ) {
201 & boost::serialization::make_nvp(
"NoiseModelFactor1",
202 boost::serialization::base_object<Base>(*
this));
212 template <
typename VALUE>
219 template<
class VALUE>
240 typedef std::shared_ptr<NonlinearEquality1<VALUE> >
shared_ptr;
259 return std::static_pointer_cast<gtsam::NonlinearFactor>(
285 std::cout <<
s <<
": NonlinearEquality1(" << keyFormatter(this->
key())
295 #if GTSAM_ENABLE_BOOST_SERIALIZATION
296 friend class boost::serialization::access;
298 template<
class ARCHIVE>
299 void serialize(ARCHIVE & ar,
const unsigned int ) {
302 & boost::serialization::make_nvp(
"NoiseModelFactor1",
303 boost::serialization::base_object<Base>(*
this));
304 ar & BOOST_SERIALIZATION_NVP(
value_);
310 template <
typename VALUE>
312 :
Testable<NonlinearEquality1<VALUE> > {};
347 return std::static_pointer_cast<gtsam::NonlinearFactor>(
355 if (H1) *H1 = -Matrix::Identity(
p,
p);
356 if (H2) *H2 = Matrix::Identity(
p,
p);
373 #if GTSAM_ENABLE_BOOST_SERIALIZATION
374 friend class boost::serialization::access;
376 template <
class ARCHIVE>
377 void serialize(ARCHIVE& ar,
const unsigned int ) {
379 ar& boost::serialization::make_nvp(
380 "NoiseModelFactor2", boost::serialization::base_object<Base>(*
this));
386 template <
typename VALUE>
const Symbol key1('v', 1)
NonlinearEquality()
Default constructor - only for serialization.
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
std::shared_ptr< This > shared_ptr
Array< double, 1, 3 > e(1./3., 0.5, 2.)
Concept check for values that can be used in unit tests.
NonlinearEquality(Key j, const T &feasible, const CompareFunction &_compare=std::bind(traits< T >::Equals, std::placeholders::_1, std::placeholders::_2, 1e-9))
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
NonlinearEqualityConstraint Base
gtsam::NonlinearFactor::shared_ptr clone() const override
gtsam::NonlinearFactor::shared_ptr clone() const override
NonlinearEquality(Key j, const T &feasible, double error_gain, const CompareFunction &_compare=std::bind(traits< T >::Equals, std::placeholders::_1, std::placeholders::_2, 1e-9))
NonlinearEquality1(const X &value, Key key, double mu=1000.0)
Nonlinear equality constraints in constrained optimization.
std::function< bool(const T &, const T &)> CompareFunction
Function that compares two values.
Vector unwhitenedError(const Values &x, OptionalMatrixVecType H=nullptr) const override
SharedNoiseModel noiseModel_
FastVector< Key > KeyVector
Define collection type once and for all - also used in wrappers.
NonlinearEquality2< T > This
std::shared_ptr< NonlinearEquality1< VALUE > > shared_ptr
fixed value for variable
KeyFormatter DefaultKeyFormatter
Assign default key formatter.
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
print
Vector unwhitenedError(const Values &x, OptionalMatrixVecType H=nullptr) const override
NonlinearEquality1< VALUE > This
const Symbol key2('v', 2)
const SharedNoiseModel & noiseModel() const
access to the noise model
std::function< std::string(Key)> KeyFormatter
Typedef for a function to format a key, i.e. to convert it to a string.
std::shared_ptr< This > shared_ptr
shared_ptr to this class
double error(const Values &c) const override
Actual error function calculation.
noiseModel::Diagonal::shared_ptr SharedDiagonal
double dot(const V1 &a, const V2 &b)
static shared_ptr All(size_t dim)
Base class and basic functions for Manifold types.
~NonlinearEquality2() override
bool equals(const NonlinearFactor &f, double tol=1e-9) const override
Vector evaluateError(const T &x1, const T &x2, OptionalMatrixType H1=nullptr, OptionalMatrixType H2=nullptr) const
g(x) with optional derivative2
Vector unwhitenedError(const Values &x, OptionalMatrixVecType H=nullptr) const override
noiseModel::Diagonal::shared_ptr model
Vector evaluateError(const X &x1, OptionalMatrixType H=nullptr) const
g(x) with optional derivative
std::shared_ptr< NonlinearEquality2< T > > shared_ptr
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
Non-linear factor base classes.
std::vector< Matrix > * OptionalMatrixVecType
~NonlinearEquality1() override
~NonlinearEquality() override
NonlinearEquality1()
Default constructor to allow for serialization.
gtsam::NonlinearFactor::shared_ptr clone() const override
const KeyVector & keys() const
Access the factor's involved variable keys.
NonlinearEquality2(Key key1, Key key2, double mu=1e4)
NonlinearEquality< VALUE > This
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
Print.
#define GTSAM_CONCEPT_TESTABLE_TYPE(T)
NonlinearEqualityConstraint Base
void Print(const CONTAINER &keys, const string &s, const KeyFormatter &keyFormatter)
bool equals(const NonlinearFactor &f, double tol=1e-9) const override
virtual bool feasible(const Values &x, const double tolerance=1e-5) const
Matrix * OptionalMatrixType
GaussianFactor::shared_ptr linearize(const Values &x) const override
Linearize is over-written, because base linearization tries to whiten.
std::uint64_t Key
Integer nonlinear key type.
Vector evaluateError(const T &xj, OptionalMatrixType H=nullptr) const
Error function.
#define GTSAM_CONCEPT_MANIFOLD_TYPE(T)
#define GTSAM_MAKE_ALIGNED_OPERATOR_NEW
Pose3 x2(Rot3::Ypr(0.0, 0.0, 0.0), l2)
gtsam
Author(s):
autogenerated on Wed Mar 19 2025 03:02:33