Go to the documentation of this file.
23 #include <gtsam/config.h>
63 typedef std::shared_ptr<ExpressionFactor<T> >
shared_ptr;
85 void print(
const std::string&
s =
"",
120 return std::shared_ptr<JacobianFactor>();
124 if (noiseModel_ && noiseModel_->isConstrained()) {
125 noiseModel = std::static_pointer_cast<noiseModel::Constrained>(
126 noiseModel_)->unit();
130 std::shared_ptr<JacobianFactor> factor(
138 Ab.matrix().setZero();
149 noiseModel_->WhitenSystem(
Ab.matrix(),
b);
152 return std::move(factor);
157 return std::static_pointer_cast<gtsam::NonlinearFactor>(
174 throw std::invalid_argument(
"ExpressionFactor: no NoiseModel.");
175 if (noiseModel_->dim() !=
Dim)
176 throw std::invalid_argument(
177 "ExpressionFactor was created with a NoiseModel of incorrect dimension.");
190 std::map<Key, int> keyedDims;
199 throw std::runtime_error(
"ExpressionFactor::expression not provided: cannot deserialize.");
203 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
204 template <
class Archive>
206 void save(Archive& ar,
const unsigned int )
const {
208 ar << boost::serialization::make_nvp(
"measured_", this->measured_);
213 template <
class Archive>
214 void load(Archive& ar,
const unsigned int ) {
216 ar >> boost::serialization::make_nvp(
"measured_", this->measured_);
221 BOOST_SERIALIZATION_SPLIT_MEMBER()
223 friend class
boost::serialization::access;
234 template <
typename T>
248 template <
typename T,
typename... Args>
264 throw std::runtime_error(
265 "ExpressionFactorN::expression not provided: cannot deserialize.");
290 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
291 friend class boost::serialization::access;
292 template <
class ARCHIVE>
293 void serialize(ARCHIVE &ar,
const unsigned int ) {
294 ar &boost::serialization::make_nvp(
301 template <
typename T,
typename... Args>
303 :
public Testable<ExpressionFactorN<T, Args...>> {};
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
T measured_
the measurement to be compared with the expression
Concept check for values that can be used in unit tests.
std::shared_ptr< ExpressionFactor< T > > shared_ptr
std::vector< T, typename internal::FastDefaultVectorAllocator< T >::type > FastVector
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
ExpressionFactor(const SharedNoiseModel &noiseModel, const T &measurement)
Default constructor, for serialization.
static const std::size_t NARY_EXPRESSION_SIZE
Eigen::Triplet< double > T
virtual Expression< T > expression(const ArrayNKeys &keys) const
KeyFormatter DefaultKeyFormatter
Assign default key formatter.
ExpressionFactor< T > This
Expression< T > expression_
the expression that is AD enabled
virtual Expression< T > expression() const
std::function< std::string(Key)> KeyFormatter
Typedef for a function to format a key, i.e. to convert it to a string.
void initialize(const Expression< T > &expression)
Initialize with constructor arguments.
std::shared_ptr< GaussianFactor > linearize(const Values &x) const override
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
noiseModel::Diagonal::shared_ptr SharedDiagonal
bool equals(const NonlinearFactor &f, double tol=1e-9) const override
ExpressionFactorN()=default
Default constructor, for serialization.
Expression< T > expression() const override
Return an expression that predicts the measurement given Values.
noiseModel::Base::shared_ptr SharedNoiseModel
std::array< Key, NARY_EXPRESSION_SIZE > ArrayNKeys
const T & measured() const
const gtsam::Symbol key('X', 0)
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
Non-linear factor base classes.
std::vector< Matrix > * OptionalMatrixVecType
void save(const Matrix &A, const string &s, const string &filename)
Vector unwhitenedError(const Values &x, OptionalMatrixVecType H=nullptr) const override
GTSAM_CONCEPT_ASSERT(IsTestable< T >)
bool equals(const NonlinearFactor &f, double tol) const override
equals relies on Testable traits being defined for T
KeyVector keys_
The keys involved in this factor.
void Print(const CONTAINER &keys, const string &s, const KeyFormatter &keyFormatter)
~ExpressionFactor() override
Destructor.
gtsam::NonlinearFactor::shared_ptr clone() const override
#define GTSAM_MAKE_ALIGNED_OPERATOR_NEW_IF(NeedsToAlign)
FastVector< int > dims_
dimensions of the Jacobian matrices
ExpressionFactor(const SharedNoiseModel &noiseModel, const T &measurement, const Expression< T > &expression)
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
print relies on Testable traits being defined for T
std::uint64_t Key
Integer nonlinear key type.
Expressions for Block Automatic Differentiation.
virtual Vector unwhitenedError(const Values &x, OptionalMatrixVecType H=nullptr) const =0
static Point2 measurement(323.0, 240.0)
ExpressionFactorN(const ArrayNKeys &keys, const SharedNoiseModel &noiseModel, const T &measurement)
Constructor takes care of keys, but still need to call initialize.
gtsam
Author(s):
autogenerated on Sat Nov 16 2024 04:02:16