23 #include <gtsam/config.h> 44 class ExpressionFactor:
public NoiseModelFactor {
58 typedef boost::shared_ptr<ExpressionFactor<T> >
shared_ptr;
80 void print(
const std::string&
s =
"",
100 boost::optional<std::vector<Matrix>&>
H = boost::none)
const override {
115 return boost::shared_ptr<JacobianFactor>();
125 boost::shared_ptr<JacobianFactor> factor(
169 throw std::invalid_argument(
"ExpressionFactor: no NoiseModel.");
171 throw std::invalid_argument(
172 "ExpressionFactor was created with a NoiseModel of incorrect dimension.");
185 std::map<Key, int> keyedDims;
186 expression_.
dims(keyedDims);
194 throw std::runtime_error(
"ExpressionFactor::expression not provided: cannot deserialize.");
199 template <
class Archive>
200 void save(Archive& ar,
const unsigned int )
const {
202 ar << boost::serialization::make_nvp(
"measured_", this->measured_);
207 template <
class Archive>
208 void load(Archive& ar,
const unsigned int ) {
210 ar >> boost::serialization::make_nvp(
"measured_", this->measured_);
215 BOOST_SERIALIZATION_SPLIT_MEMBER()
217 friend class
boost::serialization::access;
227 template <
typename T>
241 template <
typename T,
typename... Args>
257 throw std::runtime_error(
258 "ExpressionFactorN::expression not provided: cannot deserialize.");
269 for (
const auto &
key : keys)
283 friend class boost::serialization::access;
284 template <
class ARCHIVE>
286 ar &boost::serialization::make_nvp(
292 template <
typename T,
typename... Args>
294 :
public Testable<ExpressionFactorN<T, Args...>> {};
298 #if defined(GTSAM_ALLOW_DEPRECATED_SINCE_V41) 307 template <
typename T,
typename A1,
typename A2>
311 ~ExpressionFactor2()
override {}
314 Vector evaluateError(
const A1 &a1,
const A2 &a2,
315 boost::optional<Matrix &> H1 = boost::none,
316 boost::optional<Matrix &> H2 = boost::none)
const {
320 std::vector<Matrix>
H(2);
322 if (H1) (*H1) = H[0];
323 if (H2) (*H2) = H[1];
330 throw std::runtime_error(
331 "ExpressionFactor2::expression not provided: cannot deserialize.");
341 ExpressionFactor2() {}
const T & measured() const
double error(const Values &c) const override
gtsam::NonlinearFactor::shared_ptr clone() const override
bool equals(const NonlinearFactor &f, double tol=1e-9) const override
Concept check for values that can be used in unit tests.
std::array< Key, NARY_EXPRESSION_SIZE > ArrayNKeys
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
print relies on Testable traits being defined for T
Expression< T > expression() const override
Return an expression that predicts the measurement given Values.
void insert(Key j, const Value &val)
T valueAndDerivatives(const Values &values, const KeyVector &keys, const FastVector< int > &dims, std::vector< Matrix > &H) const
private version that takes keys and dimensions, returns derivatives
const Matrix & matrix() const
virtual Expression< T > expression(const ArrayNKeys &keys) const
void initialize(const Expression< T > &expression)
Initialize with constructor arguments.
KeyVector keys_
The keys involved in this factor.
Vector unwhitenedError(const Values &x, boost::optional< std::vector< Matrix > & > H=boost::none) const override
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
ExpressionFactor(const SharedNoiseModel &noiseModel, const T &measurement, const Expression< T > &expression)
static const KeyFormatter DefaultKeyFormatter
ExpressionFactor(const SharedNoiseModel &noiseModel, const T &measurement)
Default constructor, for serialization.
const SharedNoiseModel & noiseModel() const
access to the noise model
virtual bool active(const Values &) const
Expressions for Block Automatic Differentiation.
#define GTSAM_MAKE_ALIGNED_OPERATOR_NEW_IF(NeedsToAlign)
const Symbol key1('v', 1)
~ExpressionFactor() override
Destructor.
virtual Expression< T > expression() const
T valueAndJacobianMap(const Values &values, internal::JacobianMap &jacobians) const
brief Return value and derivatives, reverse AD version
KeysAndDims keysAndDims() const
boost::shared_ptr< This > shared_ptr
void load(Archive &ar, const unsigned int)
Eigen::Triplet< double > T
std::function< std::string(Key)> KeyFormatter
Typedef for a function to format a key, i.e. to convert it to a string.
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
FastVector< int > dims_
dimensions of the Jacobian matrices
void dims(std::map< Key, int > &map) const
Return dimensions for each argument, as a map.
void save(Archive &ar, const unsigned int) const
Save to an archive: just saves the base class.
noiseModel::Diagonal::shared_ptr SharedDiagonal
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
SharedNoiseModel noiseModel_
Non-linear factor base classes.
const KeyVector & keys() const
Access the factor's involved variable keys.
bool equals(const NonlinearFactor &f, double tol) const override
equals relies on Testable traits being defined for T
const Symbol key2('v', 2)
T value(const Values &values, boost::optional< std::vector< Matrix > & > H=boost::none) const
Return value and optional derivatives, reverse AD version Notes: this is not terribly efficient...
ExpressionFactor< T > This
Expression< T > expression_
the expression that is AD enabled
ExpressionFactorN(const ArrayNKeys &keys, const SharedNoiseModel &noiseModel, const T &measurement)
Constructor takes care of keys, but still need to call initialize.
boost::shared_ptr< ExpressionFactor< T > > shared_ptr
std::vector< T, typename internal::FastDefaultVectorAllocator< T >::type > FastVector
T measured_
the measurement to be compared with the expression
boost::shared_ptr< GaussianFactor > linearize(const Values &x) const override
void serialize(ARCHIVE &ar, const unsigned int)
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
BOOST_CONCEPT_ASSERT((IsTestable< T >))
std::uint64_t Key
Integer nonlinear key type.
void Print(const CONTAINER &keys, const string &s, const KeyFormatter &keyFormatter)
noiseModel::Base::shared_ptr SharedNoiseModel