SmartStereoProjectionPoseFactor.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 
23 
24 namespace gtsam {
25 
27  const SharedNoiseModel& sharedNoiseModel,
29  const boost::optional<Pose3>& body_P_sensor)
30  : Base(sharedNoiseModel, params, body_P_sensor) {}
31 
33  const StereoPoint2& measured, const Key& poseKey,
34  const boost::shared_ptr<Cal3_S2Stereo>& K) {
35  Base::add(measured, poseKey);
36  K_all_.push_back(K);
37 }
38 
40  const std::vector<StereoPoint2>& measurements, const KeyVector& poseKeys,
41  const std::vector<boost::shared_ptr<Cal3_S2Stereo>>& Ks) {
42  assert(measurements.size() == poseKeys.size());
43  assert(poseKeys.size() == Ks.size());
44  Base::add(measurements, poseKeys);
45  K_all_.insert(K_all_.end(), Ks.begin(), Ks.end());
46 }
47 
49  const std::vector<StereoPoint2>& measurements, const KeyVector& poseKeys,
50  const boost::shared_ptr<Cal3_S2Stereo>& K) {
51  assert(poseKeys.size() == measurements.size());
52  for (size_t i = 0; i < measurements.size(); i++) {
53  Base::add(measurements[i], poseKeys[i]);
54  K_all_.push_back(K);
55  }
56 }
57 
59  const std::string& s, const KeyFormatter& keyFormatter) const {
60  std::cout << s << "SmartStereoProjectionPoseFactor, z = \n ";
61  for (const boost::shared_ptr<Cal3_S2Stereo>& K : K_all_) {
62  K->print("calibration = ");
63  }
64  Base::print("", keyFormatter);
65 }
66 
68  double tol) const {
70  dynamic_cast<const SmartStereoProjectionPoseFactor*>(&p);
71 
72  return e && Base::equals(p, tol);
73 }
74 
76  if (this->active(values)) {
77  return this->totalReprojectionError(cameras(values));
78  } else { // else of active flag
79  return 0.0;
80  }
81 }
82 
83 SmartStereoProjectionPoseFactor::Base::Cameras
85  assert(keys_.size() == K_all_.size());
86  Base::Cameras cameras;
87  for (size_t i = 0; i < keys_.size(); i++) {
88  Pose3 pose = values.at<Pose3>(keys_[i]);
89  if (Base::body_P_sensor_) {
90  pose = pose.compose(*(Base::body_P_sensor_));
91  }
92  cameras.push_back(StereoCamera(pose, K_all_[i]));
93  }
94  return cameras;
95 }
96 
97 } // \ namespace gtsam
const gtsam::Key poseKey
bool equals(const This &other, double tol=1e-9) const
check equality
Definition: Factor.cpp:42
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) 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:72
double totalReprojectionError(const Cameras &cameras, boost::optional< Point3 > externalPoint=boost::none) const
void add(const StereoPoint2 &measured, const Key &poseKey, const boost::shared_ptr< Cal3_S2Stereo > &K)
bool equals(const NonlinearFactor &p, double tol=1e-9) const override
equals
Smart stereo factor on poses, assuming camera calibration is fixed.
virtual bool active(const Values &) const
graph add(boost::make_shared< UnaryFactor >(1, 0.0, 0.0, unaryNoise))
FastVector< Key > KeyVector
Define collection type once and for all - also used in wrappers.
Definition: Key.h:86
Class compose(const Class &g) const
Definition: Lie.h:47
double error(const Values &values) const override
const ValueType at(Key j) const
Definition: Values-inl.h:342
static const Pose3 pose(Rot3(Vector3(1,-1,-1).asDiagonal()), Point3(0, 0, 0.5))
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
SmartStereoProjectionPoseFactor(const SharedNoiseModel &sharedNoiseModel, const SmartStereoProjectionParams &params=SmartStereoProjectionParams(), const boost::optional< Pose3 > &body_P_sensor=boost::none)
Array< double, 1, 3 > e(1./3., 0.5, 2.)
RealScalar s
virtual void print(const std::string &s="Factor", const KeyFormatter &formatter=DefaultKeyFormatter) const
print
Definition: Factor.cpp:29
static SmartStereoProjectionParams params
Base::Cameras cameras(const Values &values) const override
traits
Definition: chartTesting.h:28
std::vector< boost::shared_ptr< Cal3_S2Stereo > > K_all_
shared pointer to calibration object (one for each camera)
float * p
const G double tol
Definition: Group.h:83
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:61
noiseModel::Base::shared_ptr SharedNoiseModel
Definition: NoiseModel.h:734


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:44:16