SmartStereoProjectionFactorPP.cpp
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 
20 
21 namespace gtsam {
22 
24  const SharedNoiseModel& sharedNoiseModel,
26  : Base(sharedNoiseModel, params) {} // note: no extrinsic specified!
27 
29  const StereoPoint2& measured,
30  const Key& w_P_body_key, const Key& body_P_cam_key,
31  const std::shared_ptr<Cal3_S2Stereo>& K) {
32  // we index by cameras..
33  Base::add(measured, w_P_body_key);
34  // but we also store the extrinsic calibration keys in the same order
35  world_P_body_keys_.push_back(w_P_body_key);
36  body_P_cam_keys_.push_back(body_P_cam_key);
37 
38  // pose keys are assumed to be unique (1 observation per time stamp), but calibration can be shared
39  if(std::find(keys_.begin(), keys_.end(), body_P_cam_key) == keys_.end())
40  keys_.push_back(body_P_cam_key); // add only unique keys
41 
42  K_all_.push_back(K);
43 }
44 
46  const std::vector<StereoPoint2>& measurements,
47  const KeyVector& world_P_body_keys, const KeyVector& body_P_cam_keys,
48  const std::vector<std::shared_ptr<Cal3_S2Stereo>>& Ks) {
49  assert(world_P_body_keys.size() == measurements.size());
50  assert(world_P_body_keys.size() == body_P_cam_keys.size());
51  assert(world_P_body_keys.size() == Ks.size());
52  for (size_t i = 0; i < measurements.size(); i++) {
53  Base::add(measurements[i], world_P_body_keys[i]);
54  // pose keys are assumed to be unique (1 observation per time stamp), but calibration can be shared
55  if(std::find(keys_.begin(), keys_.end(), body_P_cam_keys[i]) == keys_.end())
56  keys_.push_back(body_P_cam_keys[i]); // add only unique keys
57 
58  world_P_body_keys_.push_back(world_P_body_keys[i]);
59  body_P_cam_keys_.push_back(body_P_cam_keys[i]);
60 
61  K_all_.push_back(Ks[i]);
62  }
63 }
64 
66  const std::vector<StereoPoint2>& measurements,
67  const KeyVector& world_P_body_keys, const KeyVector& body_P_cam_keys,
68  const std::shared_ptr<Cal3_S2Stereo>& K) {
69  assert(world_P_body_keys.size() == measurements.size());
70  assert(world_P_body_keys.size() == body_P_cam_keys.size());
71  for (size_t i = 0; i < measurements.size(); i++) {
72  Base::add(measurements[i], world_P_body_keys[i]);
73  // pose keys are assumed to be unique (1 observation per time stamp), but calibration can be shared
74  if(std::find(keys_.begin(), keys_.end(), body_P_cam_keys[i]) == keys_.end())
75  keys_.push_back(body_P_cam_keys[i]); // add only unique keys
76 
77  world_P_body_keys_.push_back(world_P_body_keys[i]);
78  body_P_cam_keys_.push_back(body_P_cam_keys[i]);
79 
80  K_all_.push_back(K);
81  }
82 }
83 
85  const std::string& s, const KeyFormatter& keyFormatter) const {
86  std::cout << s << "SmartStereoProjectionFactorPP: \n ";
87  for (size_t i = 0; i < K_all_.size(); i++) {
88  K_all_[i]->print("calibration = ");
89  std::cout << " extrinsic pose key: " << keyFormatter(body_P_cam_keys_[i]) << std::endl;
90  }
91  Base::print("", keyFormatter);
92 }
93 
95  double tol) const {
97  dynamic_cast<const SmartStereoProjectionFactorPP*>(&p);
98 
99  return e && Base::equals(p, tol) &&
101 }
102 
104  if (this->active(values)) {
105  return this->totalReprojectionError(cameras(values));
106  } else { // else of active flag
107  return 0.0;
108  }
109 }
110 
113  assert(world_P_body_keys_.size() == K_all_.size());
114  assert(world_P_body_keys_.size() == body_P_cam_keys_.size());
116  for (size_t i = 0; i < world_P_body_keys_.size(); i++) {
117  Pose3 w_P_body = values.at<Pose3>(world_P_body_keys_[i]);
118  Pose3 body_P_cam = values.at<Pose3>(body_P_cam_keys_[i]);
119  Pose3 w_P_cam = w_P_body.compose(body_P_cam);
120  cameras.push_back(StereoCamera(w_P_cam, K_all_[i]));
121  }
122  return cameras;
123 }
124 
125 } // \ namespace gtsam
const KeyVector & getExtrinsicPoseKeys() const
equals
virtual void print(const std::string &s="Factor", const KeyFormatter &formatter=DefaultKeyFormatter) const
print
Definition: Factor.cpp:29
const ValueType at(Key j) const
Definition: Values-inl.h:204
CameraSet< Camera > Cameras
double error(const Values &values) const override
leaf::MyValues values
static Cal3_S2 K(500, 500, 0.1, 640/2, 480/2)
KeyVector keys_
The keys involved in this factor.
Definition: Factor.h:87
static const SmartProjectionParams params
double totalReprojectionError(const Cameras &cameras, std::optional< Point3 > externalPoint={}) const
Array< double, 1, 3 > e(1./3., 0.5, 2.)
RealScalar s
KeyVector body_P_cam_keys_
The keys corresponding to the extrinsic pose calibration for each view (pose that transform from came...
std::vector< std::shared_ptr< Cal3_S2Stereo > > K_all_
shared pointer to calibration object (one for each camera)
Class compose(const Class &g) const
Definition: Lie.h:48
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
const ZVector & measured() const
Return the 2D measurements (ZDim, in general).
traits
Definition: chartTesting.h:28
void add(const StereoPoint2 &measured, const Key &world_P_body_key, const Key &body_P_cam_key, const std::shared_ptr< Cal3_S2Stereo > &K)
virtual bool active(const Values &) const
Base::Cameras cameras(const Values &values) const override
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
float * p
graph add(PriorFactor< Pose2 >(1, priorMean, priorNoise))
const G double tol
Definition: Group.h:86
SmartStereoProjectionFactorPP(const SharedNoiseModel &sharedNoiseModel, const SmartStereoProjectionParams &params=SmartStereoProjectionParams())
FastVector< Key > KeyVector
Define collection type once and for all - also used in wrappers.
Definition: Key.h:86
bool equals(const NonlinearFactor &p, double tol=1e-9) const override
equals
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:102
noiseModel::Base::shared_ptr SharedNoiseModel
Definition: NoiseModel.h:741
bool equals(const This &other, double tol=1e-9) const
check equality
Definition: Factor.cpp:42
KeyVector world_P_body_keys_
The keys corresponding to the pose of the body (with respect to an external world frame) for each vie...
Smart stereo factor on poses and extrinsic calibration.


gtsam
Author(s):
autogenerated on Tue Jul 4 2023 02:35:52