PinholeFactor.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 
19 #pragma once
20 
21 namespace gtsam {
22 template <typename T>
23 struct traits;
24 }
25 
28 #include <gtsam/geometry/Pose3.h>
30 
31 namespace gtsam {
32 
33 class PinholeFactor : public SmartFactorBase<PinholeCamera<Cal3Bundler> > {
34  public:
37  PinholeFactor(const SharedNoiseModel& sharedNoiseModel,
38  std::optional<Pose3> body_P_sensor = {},
39  size_t expectedNumberCameras = 10)
40  : Base(sharedNoiseModel, body_P_sensor, expectedNumberCameras) {}
41  double error(const Values& values) const override { return 0.0; }
42  std::shared_ptr<GaussianFactor> linearize(
43  const Values& values) const override {
44  return std::shared_ptr<GaussianFactor>(new JacobianFactor());
45  }
46 };
47 
49 template <>
50 struct traits<PinholeFactor> : public Testable<PinholeFactor> {};
51 
52 } // namespace gtsam
SmartFactorBase< PinholeCamera< Cal3Bundler > > Base
Definition: PinholeFactor.h:35
leaf::MyValues values
Base class to create smart factors on poses or cameras.
Base class for all pinhole cameras.
Base class for smart factors. This base class has no internal point, but it has a measurement...
double error(const Values &values) const override
Definition: PinholeFactor.h:41
PinholeFactor(const SharedNoiseModel &sharedNoiseModel, std::optional< Pose3 > body_P_sensor={}, size_t expectedNumberCameras=10)
Definition: PinholeFactor.h:37
traits
Definition: chartTesting.h:28
std::shared_ptr< GaussianFactor > linearize(const Values &values) const override
Definition: PinholeFactor.h:42
3D Pose
Calibration used by Bundler.
noiseModel::Base::shared_ptr SharedNoiseModel
Definition: NoiseModel.h:741


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