DummyFactor.cpp
Go to the documentation of this file.
1 
9 
10 namespace gtsam {
11 
12 /* ************************************************************************* */
13 DummyFactor::DummyFactor(const Key& key1, size_t dim1, const Key& key2, size_t dim2)
15 {
16  dims_.push_back(dim1);
17  dims_.push_back(dim2);
18  if (dim1 > dim2)
19  rowDim_ = dim1;
20  else
21  rowDim_ = dim2;
22 }
23 
24 /* ************************************************************************* */
25 void DummyFactor::print(const std::string& s, const KeyFormatter& keyFormatter) const {
26  std::cout << s << " DummyFactor dim = " << rowDim_ << ", keys = { ";
27  for(Key key: this->keys()) { std::cout << keyFormatter(key) << " "; }
28  std::cout << "}" << std::endl;
29 }
30 
31 /* ************************************************************************* */
32 bool DummyFactor::equals(const NonlinearFactor& f, double tol) const {
33  const DummyFactor* e = dynamic_cast<const DummyFactor*>(&f);
34  return e && Base::equals(f, tol) && dims_ == e->dims_ && rowDim_ == e->rowDim_;
35 }
36 
37 /* ************************************************************************* */
38 std::shared_ptr<GaussianFactor>
40  // Only linearize if the factor is active
41  if (!this->active(c))
42  return std::shared_ptr<JacobianFactor>();
43 
44  // Fill in terms with zero matrices
45  std::vector<std::pair<Key, Matrix> > terms(this->size());
46  for(size_t j=0; j<this->size(); ++j) {
47  terms[j].first = keys()[j];
48  terms[j].second = Matrix::Zero(rowDim_, dims_[j]);
49  }
50 
53  new JacobianFactor(terms, Vector::Zero(rowDim_), model));
54 }
55 
56 /* ************************************************************************* */
57 
58 } // \namespace gtsam
59 
60 
61 
62 
const gtsam::Symbol key('X', 0)
noiseModel::Diagonal::shared_ptr model
size_t size() const
Definition: Factor.h:159
Scalar Scalar * c
Definition: benchVecAdd.cpp:17
static shared_ptr Create(size_t dim)
Definition: NoiseModel.h:610
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
Definition: DummyFactor.cpp:25
size_t rowDim_
choose dimension for the rows
const Symbol key1('v', 1)
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
Array< double, 1, 3 > e(1./3., 0.5, 2.)
RealScalar s
std::function< std::string(Key)> KeyFormatter
Typedef for a function to format a key, i.e. to convert it to a string.
Definition: Key.h:35
std::shared_ptr< This > shared_ptr
shared_ptr to this class
traits
Definition: chartTesting.h:28
virtual bool active(const Values &) const
const KeyVector & keys() const
Access the factor&#39;s involved variable keys.
Definition: Factor.h:142
bool equals(const NonlinearFactor &f, double tol=1e-9) const override
Definition: DummyFactor.cpp:32
const G double tol
Definition: Group.h:86
std::shared_ptr< GaussianFactor > linearize(const Values &c) const override
Definition: DummyFactor.cpp:39
FastVector< Key > KeyVector
Define collection type once and for all - also used in wrappers.
Definition: Key.h:86
std::shared_ptr< Diagonal > shared_ptr
Definition: NoiseModel.h:307
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:102
std::ptrdiff_t j
const Symbol key2('v', 2)
bool equals(const This &other, double tol=1e-9) const
check equality
Definition: Factor.cpp:42


gtsam
Author(s):
autogenerated on Tue Jul 4 2023 02:34:11