DummyFactor.cpp
Go to the documentation of this file.
1 
9 
10 #include <boost/assign/list_of.hpp>
11 
12 using namespace boost::assign;
13 
14 namespace gtsam {
15 
16 /* ************************************************************************* */
17 DummyFactor::DummyFactor(const Key& key1, size_t dim1, const Key& key2, size_t dim2)
18 : NonlinearFactor(cref_list_of<2>(key1)(key2))
19 {
20  dims_.push_back(dim1);
21  dims_.push_back(dim2);
22  if (dim1 > dim2)
23  rowDim_ = dim1;
24  else
25  rowDim_ = dim2;
26 }
27 
28 /* ************************************************************************* */
29 void DummyFactor::print(const std::string& s, const KeyFormatter& keyFormatter) const {
30  std::cout << s << " DummyFactor dim = " << rowDim_ << ", keys = { ";
31  for(Key key: this->keys()) { std::cout << keyFormatter(key) << " "; }
32  std::cout << "}" << std::endl;
33 }
34 
35 /* ************************************************************************* */
36 bool DummyFactor::equals(const NonlinearFactor& f, double tol) const {
37  const DummyFactor* e = dynamic_cast<const DummyFactor*>(&f);
38  return e && Base::equals(f, tol) && dims_ == e->dims_ && rowDim_ == e->rowDim_;
39 }
40 
41 /* ************************************************************************* */
42 boost::shared_ptr<GaussianFactor>
44  // Only linearize if the factor is active
45  if (!this->active(c))
46  return boost::shared_ptr<JacobianFactor>();
47 
48  // Fill in terms with zero matrices
49  std::vector<std::pair<Key, Matrix> > terms(this->size());
50  for(size_t j=0; j<this->size(); ++j) {
51  terms[j].first = keys()[j];
52  terms[j].second = Matrix::Zero(rowDim_, dims_[j]);
53  }
54 
57  new JacobianFactor(terms, Vector::Zero(rowDim_), model));
58 }
59 
60 /* ************************************************************************* */
61 
62 } // \namespace gtsam
63 
64 
65 
66 
bool equals(const This &other, double tol=1e-9) const
check equality
Definition: Factor.cpp:42
noiseModel::Diagonal::shared_ptr model
Scalar Scalar * c
Definition: benchVecAdd.cpp:17
virtual bool active(const Values &) const
static shared_ptr Create(size_t dim)
Definition: NoiseModel.h:608
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
Definition: DummyFactor.cpp:29
const Symbol key1('v', 1)
size_t rowDim_
choose dimension for the rows
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
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
Array< double, 1, 3 > e(1./3., 0.5, 2.)
RealScalar s
boost::shared_ptr< GaussianFactor > linearize(const Values &c) const override
Definition: DummyFactor.cpp:43
boost::shared_ptr< Diagonal > shared_ptr
Definition: NoiseModel.h:301
boost::shared_ptr< This > shared_ptr
shared_ptr to this class
traits
Definition: chartTesting.h:28
size_t size() const
Definition: Factor.h:135
const KeyVector & keys() const
Access the factor&#39;s involved variable keys.
Definition: Factor.h:124
const Symbol key2('v', 2)
bool equals(const NonlinearFactor &f, double tol=1e-9) const override
Definition: DummyFactor.cpp:36
const G double tol
Definition: Group.h:83
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:61
std::ptrdiff_t j


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:42:00