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 NoiseModelFactorN ?
36 
37  public:
38 
39  typedef VALUE T;
40 
41  private:
42 
45 
47 
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
64  typedef typename std::shared_ptr<TransformBtwRobotsUnaryFactor> shared_ptr;
65 
68 
71  const gtsam::Values& valA, const gtsam::Values& valB,
72  const SharedGaussian& model) :
74  model_(model){
75 
76  setValAValB(valA, valB);
77 
78  }
79 
81 
82 
84  gtsam::NonlinearFactor::shared_ptr clone() const override { return std::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  std::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 std::shared_ptr<gtsam::JacobianFactor>();
146 
147  //std::cout<<"About to linearize"<<std::endl;
149  std::vector<gtsam::Matrix> A(this->size());
151  A1 = A[0];
152 
155  }
156 
157 
158  /* ************************************************************************* */
160 
161  T orgA_T_currA = valA_.at<T>(keyA_);
162  T orgB_T_currB = valB_.at<T>(keyB_);
163  T orgA_T_orgB = x.at<T>(key_);
164 
165  T currA_T_currB_pred;
166  if (H) {
167  Matrix H_compose, H_between1;
168  T orgA_T_currB = orgA_T_orgB.compose(orgB_T_currB, H_compose, {});
169  currA_T_currB_pred = orgA_T_currA.between(orgA_T_currB, {}, H_between1);
170  (*H)[0] = H_compose * H_between1;
171  }
172  else {
173  T orgA_T_currB = orgA_T_orgB.compose(orgB_T_currB);
174  currA_T_currB_pred = orgA_T_currA.between(orgA_T_currB);
175  }
176 
177  const T& currA_T_currB_msr = measured_;
178  Vector error = currA_T_currB_msr.localCoordinates(currA_T_currB_pred);
179 
180  if (H)
181  model_->WhitenSystem(*H, error);
182  else
183  model_->whitenInPlace(error);
184 
185  return error;
186  }
187 
188  /* ************************************************************************* */
192  gtsam::Vector whitenedError(const gtsam::Values& x, std::vector<Matrix>& H) const {
193  return whitenedError(x, &H);
194  }
195 
196 
197  /* ************************************************************************* */
199 
200  T orgA_T_currA = valA_.at<T>(keyA_);
201  T orgB_T_currB = valB_.at<T>(keyB_);
202  T orgA_T_orgB = x.at<T>(key_);
203 
204  T orgA_T_currB = orgA_T_orgB.compose(orgB_T_currB);
205  T currA_T_currB_pred = orgA_T_currA.between(orgA_T_currB);
206 
207  T currA_T_currB_msr = measured_;
208  return currA_T_currB_msr.localCoordinates(currA_T_currB_pred);
209  }
210 
211  /* ************************************************************************* */
212 
213  size_t dim() const override {
214  return model_->R().rows() + model_->R().cols();
215  }
216 
217  private:
218 
219 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
220 
221  friend class boost::serialization::access;
222  template<class ARCHIVE>
223  void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
224  ar & boost::serialization::make_nvp("NonlinearFactor",
225  boost::serialization::base_object<Base>(*this));
226  //ar & BOOST_SERIALIZATION_NVP(measured_);
227  }
228 #endif
229  }; // \class TransformBtwRobotsUnaryFactor
230 
232  template<class VALUE>
234  public Testable<TransformBtwRobotsUnaryFactor<VALUE> > {
235  };
236 
237 }
gtsam::TransformBtwRobotsUnaryFactor::dim
size_t dim() const override
Definition: TransformBtwRobotsUnaryFactor.h:213
H
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
Definition: gnuplot_common_settings.hh:74
gtsam::NonlinearFactor::shared_ptr
std::shared_ptr< This > shared_ptr
Definition: NonlinearFactor.h:78
gtsam::Values::exists
bool exists(Key j) const
Definition: Values.cpp:93
s
RealScalar s
Definition: level1_cplx_impl.h:126
e
Array< double, 1, 3 > e(1./3., 0.5, 2.)
Testable.h
Concept check for values that can be used in unit tests.
x
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
Definition: gnuplot_common_settings.hh:12
gtsam::JacobianFactor
Definition: JacobianFactor.h:91
gtsam::NonlinearFactor::equals
virtual bool equals(const NonlinearFactor &f, double tol=1e-9) const
Definition: NonlinearFactor.cpp:45
measured
Point2 measured(-17, 30)
gtsam::Matrix
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:39
gtsam::Factor
Definition: Factor.h:69
gtsam::TransformBtwRobotsUnaryFactor::keyB_
gtsam::Key keyB_
Definition: TransformBtwRobotsUnaryFactor.h:53
gtsam::NonlinearFactor::active
virtual bool active(const Values &) const
Definition: NonlinearFactor.h:141
gtsam::Vector
Eigen::VectorXd Vector
Definition: Vector.h:38
gtsam::KeyVector
FastVector< Key > KeyVector
Define collection type once and for all - also used in wrappers.
Definition: Key.h:92
gtsam::DefaultKeyFormatter
KeyFormatter DefaultKeyFormatter
Assign default key formatter.
Definition: Key.cpp:30
gtsam::TransformBtwRobotsUnaryFactor::equals
bool equals(const NonlinearFactor &f, double tol=1e-9) const override
Definition: TransformBtwRobotsUnaryFactor.h:102
GTSAM_CONCEPT_LIE_TYPE
#define GTSAM_CONCEPT_LIE_TYPE(T)
Definition: Lie.h:373
gtsam::TransformBtwRobotsUnaryFactor::model_
SharedGaussian model_
Definition: TransformBtwRobotsUnaryFactor.h:55
gtsam::TransformBtwRobotsUnaryFactor::setValAValB
void setValAValB(const gtsam::Values &valA, const gtsam::Values &valB)
Definition: TransformBtwRobotsUnaryFactor.h:114
gtsam::TransformBtwRobotsUnaryFactor::T
VALUE T
Definition: TransformBtwRobotsUnaryFactor.h:39
Eigen::internal::VALUE
@ VALUE
Definition: SpecialFunctionsImpl.h:729
gtsam::Values::at
const ValueType at(Key j) const
Definition: Values-inl.h:261
A
Definition: test_numpy_dtypes.cpp:298
BetweenFactor.h
gtsam::KeyFormatter
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
gtsam::TransformBtwRobotsUnaryFactor::linearize
std::shared_ptr< gtsam::GaussianFactor > linearize(const gtsam::Values &x) const override
Definition: TransformBtwRobotsUnaryFactor.h:142
gtsam::GaussianFactor::shared_ptr
std::shared_ptr< This > shared_ptr
shared_ptr to this class
Definition: GaussianFactor.h:42
gtsam::noiseModel::Unit::Create
static shared_ptr Create(size_t dim)
Definition: NoiseModel.h:610
gtsam::TransformBtwRobotsUnaryFactor::error
double error(const gtsam::Values &x) const override
Definition: TransformBtwRobotsUnaryFactor.h:131
gtsam::TransformBtwRobotsUnaryFactor::valB_
gtsam::Values valB_
Definition: TransformBtwRobotsUnaryFactor.h:51
gtsam::TransformBtwRobotsUnaryFactor::key_
gtsam::Key key_
Definition: TransformBtwRobotsUnaryFactor.h:46
gtsam::TransformBtwRobotsUnaryFactor::Base
gtsam::NonlinearFactor Base
Definition: TransformBtwRobotsUnaryFactor.h:44
gtsam::TransformBtwRobotsUnaryFactor::shared_ptr
std::shared_ptr< TransformBtwRobotsUnaryFactor > shared_ptr
Definition: TransformBtwRobotsUnaryFactor.h:64
gtsam::SharedGaussian
noiseModel::Gaussian::shared_ptr SharedGaussian
Definition: NoiseModel.h:742
gtsam::TransformBtwRobotsUnaryFactor::clone
gtsam::NonlinearFactor::shared_ptr clone() const override
Definition: TransformBtwRobotsUnaryFactor.h:84
model
noiseModel::Diagonal::shared_ptr model
Definition: doc/Code/Pose2SLAMExample.cpp:7
gtsam::TransformBtwRobotsUnaryFactor::~TransformBtwRobotsUnaryFactor
~TransformBtwRobotsUnaryFactor() override
Definition: TransformBtwRobotsUnaryFactor.h:80
key
const gtsam::Symbol key('X', 0)
tree::f
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
Definition: testExpression.cpp:218
gtsam::TransformBtwRobotsUnaryFactor::print
void print(const std::string &s, const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
Definition: TransformBtwRobotsUnaryFactor.h:90
NonlinearFactor.h
Non-linear factor base classes.
gtsam::OptionalMatrixVecType
std::vector< Matrix > * OptionalMatrixVecType
Definition: NonlinearFactor.h:61
gtsam::b
const G & b
Definition: Group.h:79
Lie.h
Base class and basic functions for Lie types.
gtsam::TransformBtwRobotsUnaryFactor::TransformBtwRobotsUnaryFactor
TransformBtwRobotsUnaryFactor(Key key, const VALUE &measured, Key keyA, Key keyB, const gtsam::Values &valA, const gtsam::Values &valB, const SharedGaussian &model)
Definition: TransformBtwRobotsUnaryFactor.h:70
gtsam
traits
Definition: chartTesting.h:28
gtsam::Testable
Definition: Testable.h:152
gtsam::traits
Definition: Group.h:36
keyA
Key keyA
Definition: testFunctorizedFactor.cpp:36
gtsam::Values
Definition: Values.h:65
gtsam::NonlinearFactor
Definition: NonlinearFactor.h:68
GTSAM_CONCEPT_TESTABLE_TYPE
#define GTSAM_CONCEPT_TESTABLE_TYPE(T)
Definition: Testable.h:177
A1
static const double A1[]
Definition: expn.h:6
gtsam::TransformBtwRobotsUnaryFactor::unwhitenedError
gtsam::Vector unwhitenedError(const gtsam::Values &x) const
Definition: TransformBtwRobotsUnaryFactor.h:198
gtsam::TransformBtwRobotsUnaryFactor::whitenedError
gtsam::Vector whitenedError(const gtsam::Values &x, std::vector< Matrix > &H) const
Definition: TransformBtwRobotsUnaryFactor.h:192
gtsam::TransformBtwRobotsUnaryFactor::measured_
VALUE measured_
Definition: TransformBtwRobotsUnaryFactor.h:48
gtsam::TransformBtwRobotsUnaryFactor
Definition: TransformBtwRobotsUnaryFactor.h:35
gtsam::tol
const G double tol
Definition: Group.h:79
gtsam::TransformBtwRobotsUnaryFactor::This
TransformBtwRobotsUnaryFactor< VALUE > This
Definition: TransformBtwRobotsUnaryFactor.h:43
GaussianFactor.h
A factor with a quadratic error function - a Gaussian.
gtsam::TransformBtwRobotsUnaryFactor::TransformBtwRobotsUnaryFactor
TransformBtwRobotsUnaryFactor()
Definition: TransformBtwRobotsUnaryFactor.h:67
gtsam::TransformBtwRobotsUnaryFactor::whitenedError
gtsam::Vector whitenedError(const gtsam::Values &x, OptionalMatrixVecType H=nullptr) const
Definition: TransformBtwRobotsUnaryFactor.h:159
align_3::t
Point2 t(10, 10)
gtsam::Factor::size
size_t size() const
Definition: Factor.h:159
gtsam::Key
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:97
gtsam::TransformBtwRobotsUnaryFactor::keyA_
gtsam::Key keyA_
Definition: TransformBtwRobotsUnaryFactor.h:52
gtsam::TransformBtwRobotsUnaryFactor::valA_
gtsam::Values valA_
Definition: TransformBtwRobotsUnaryFactor.h:50


gtsam
Author(s):
autogenerated on Tue Jun 25 2024 03:07:31