TransformBtwRobotsUnaryFactor.h
Go to the documentation of this file.
1 /* ----------------------------------------------------------------------------
2 
3  * GTSAM Copyright 2010, Georgia Tech Research Corporation,
4  * Atlanta, Georgia 30332-0415
5  * All Rights Reserved
6  * Authors: Frank Dellaert, et al. (see THANKS for the full author list)
7 
8  * See LICENSE for the license information
9 
10  * -------------------------------------------------------------------------- */
11 
17 #pragma once
18 
22 #include <gtsam/base/Testable.h>
23 #include <gtsam/base/Lie.h>
24 
25 #include <ostream>
26 
27 namespace gtsam {
28 
34  template<class VALUE>
35  class TransformBtwRobotsUnaryFactor: public NonlinearFactor { // TODO why not NoiseModelFactor1 ?
36 
37  public:
38 
39  typedef VALUE T;
40 
41  private:
42 
45 
47 
48  VALUE measured_;
50  gtsam::Values valA_; // given values for robot A map\trajectory
51  gtsam::Values valB_; // given values for robot B map\trajectory
52  gtsam::Key keyA_; // key of robot A to which the measurement refers
53  gtsam::Key keyB_; // key of robot B to which the measurement refers
54 
56 
60 
61  public:
62 
63  // shorthand for a smart pointer to a factor
65 
68 
71  const gtsam::Values& valA, const gtsam::Values& valB,
72  const SharedGaussian& model) :
73  Base(cref_list_of<1>(key)), key_(key), measured_(measured), keyA_(keyA), keyB_(keyB),
74  model_(model){
75 
76  setValAValB(valA, valB);
77 
78  }
79 
81 
82 
84  gtsam::NonlinearFactor::shared_ptr clone() const override { return boost::make_shared<This>(*this); }
85 
86 
90  void print(const std::string& s, const KeyFormatter& keyFormatter = DefaultKeyFormatter) const override {
91  std::cout << s << "TransformBtwRobotsUnaryFactor("
92  << keyFormatter(key_) << ")\n";
93  std::cout << "MR between factor keys: "
94  << keyFormatter(keyA_) << ","
95  << keyFormatter(keyB_) << "\n";
96  measured_.print(" measured: ");
97  model_->print(" noise model: ");
98  // Base::print(s, keyFormatter);
99  }
100 
102  bool equals(const NonlinearFactor& f, double tol=1e-9) const override {
103  const This *t = dynamic_cast<const This*> (&f);
104 
105  if(t && Base::equals(f))
106  return key_ == t->key_ && measured_.equals(t->measured_);
107  else
108  return false;
109  }
110 
113  /* ************************************************************************* */
114  void setValAValB(const gtsam::Values& valA, const gtsam::Values& valB){
115  if ( (!valA.exists(keyA_)) && (!valB.exists(keyA_)) && (!valA.exists(keyB_)) && (!valB.exists(keyB_)) )
116  throw("something is wrong!");
117 
118  // TODO: make sure the two keys belong to different robots
119 
120  if (valA.exists(keyA_)){
121  valA_ = valA;
122  valB_ = valB;
123  }
124  else {
125  valA_ = valB;
126  valB_ = valA;
127  }
128  }
129 
130  /* ************************************************************************* */
131  double error(const gtsam::Values& x) const override {
132  return whitenedError(x).squaredNorm();
133  }
134 
135  /* ************************************************************************* */
141  /* This version of linearize recalculates the noise model each time */
142  boost::shared_ptr<gtsam::GaussianFactor> linearize(const gtsam::Values& x) const override {
143  // Only linearize if the factor is active
144  if (!this->active(x))
145  return boost::shared_ptr<gtsam::JacobianFactor>();
146 
147  //std::cout<<"About to linearize"<<std::endl;
148  gtsam::Matrix A1;
149  std::vector<gtsam::Matrix> A(this->size());
150  gtsam::Vector b = -whitenedError(x, A);
151  A1 = A[0];
152 
154  new gtsam::JacobianFactor(key_, A1, b, gtsam::noiseModel::Unit::Create(b.size())));
155  }
156 
157 
158  /* ************************************************************************* */
160  boost::optional<std::vector<gtsam::Matrix>&> H = boost::none) const {
161 
162  T orgA_T_currA = valA_.at<T>(keyA_);
163  T orgB_T_currB = valB_.at<T>(keyB_);
164  T orgA_T_orgB = x.at<T>(key_);
165 
166  T currA_T_currB_pred;
167  if (H) {
168  Matrix H_compose, H_between1;
169  T orgA_T_currB = orgA_T_orgB.compose(orgB_T_currB, H_compose, boost::none);
170  currA_T_currB_pred = orgA_T_currA.between(orgA_T_currB, boost::none, H_between1);
171  (*H)[0] = H_compose * H_between1;
172  }
173  else {
174  T orgA_T_currB = orgA_T_orgB.compose(orgB_T_currB);
175  currA_T_currB_pred = orgA_T_currA.between(orgA_T_currB);
176  }
177 
178  const T& currA_T_currB_msr = measured_;
179  Vector error = currA_T_currB_msr.localCoordinates(currA_T_currB_pred);
180 
181  if (H)
182  model_->WhitenSystem(*H, error);
183  else
184  model_->whitenInPlace(error);
185 
186  return error;
187  }
188 
189 
190  /* ************************************************************************* */
192 
193  T orgA_T_currA = valA_.at<T>(keyA_);
194  T orgB_T_currB = valB_.at<T>(keyB_);
195  T orgA_T_orgB = x.at<T>(key_);
196 
197  T orgA_T_currB = orgA_T_orgB.compose(orgB_T_currB);
198  T currA_T_currB_pred = orgA_T_currA.between(orgA_T_currB);
199 
200  T currA_T_currB_msr = measured_;
201  return currA_T_currB_msr.localCoordinates(currA_T_currB_pred);
202  }
203 
204  /* ************************************************************************* */
205 
206  size_t dim() const override {
207  return model_->R().rows() + model_->R().cols();
208  }
209 
210  private:
211 
214  template<class ARCHIVE>
215  void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
216  ar & boost::serialization::make_nvp("NonlinearFactor",
217  boost::serialization::base_object<Base>(*this));
218  //ar & BOOST_SERIALIZATION_NVP(measured_);
219  }
220  }; // \class TransformBtwRobotsUnaryFactor
221 
223  template<class VALUE>
225  public Testable<TransformBtwRobotsUnaryFactor<VALUE> > {
226  };
227 
228 }
bool equals(const NonlinearFactor &f, double tol=1e-9) const override
bool equals(const This &other, double tol=1e-9) const
check equality
Definition: Factor.cpp:42
void serialize(ARCHIVE &ar, const unsigned int)
bool exists(Key j) const
Definition: Values.cpp:104
Concept check for values that can be used in unit tests.
noiseModel::Diagonal::shared_ptr model
TransformBtwRobotsUnaryFactor(Key key, const VALUE &measured, Key keyA, Key keyB, const gtsam::Values &valA, const gtsam::Values &valB, const SharedGaussian &model)
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:43
A factor with a quadratic error function - a Gaussian.
TransformBtwRobotsUnaryFactor< VALUE > This
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
#define GTSAM_CONCEPT_TESTABLE_TYPE(T)
Definition: Testable.h:175
static const KeyFormatter DefaultKeyFormatter
Definition: Key.h:43
virtual bool active(const Values &) const
static shared_ptr Create(size_t dim)
Definition: NoiseModel.h:608
gtsam::Vector unwhitenedError(const gtsam::Values &x) const
Eigen::VectorXd Vector
Definition: Vector.h:38
const ValueType at(Key j) const
Definition: Values-inl.h:342
boost::shared_ptr< This > shared_ptr
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
void setValAValB(const gtsam::Values &valA, const gtsam::Values &valB)
virtual bool equals(const NonlinearFactor &f, double tol=1e-9) const
const G & b
Definition: Group.h:83
boost::shared_ptr< This > shared_ptr
shared_ptr to this class
Base class and basic functions for Lie types.
gtsam::Vector whitenedError(const gtsam::Values &x, boost::optional< std::vector< gtsam::Matrix > & > H=boost::none) const
traits
Definition: chartTesting.h:28
friend class boost::serialization::access
#define GTSAM_CONCEPT_LIE_TYPE(T)
Definition: Lie.h:356
gtsam::NonlinearFactor::shared_ptr clone() const override
boost::shared_ptr< Factor > shared_ptr
A shared_ptr to this class.
Definition: Factor.h:60
Non-linear factor base classes.
size_t size() const
Definition: Factor.h:135
void print(const std::string &s, const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
boost::shared_ptr< gtsam::GaussianFactor > linearize(const gtsam::Values &x) const override
const G double tol
Definition: Group.h:83
double error(const gtsam::Values &x) const override
Point3 measured
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
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:61
noiseModel::Gaussian::shared_ptr SharedGaussian
Definition: NoiseModel.h:735
Point2 t(10, 10)


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:51:06