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.h
Base class to create smart factors on poses or cameras.
gtsam::SmartFactorBase< PinholeCamera< Cal3Bundler > >::body_P_sensor
Pose3 body_P_sensor() const
Definition: SmartFactorBase.h:444
gtsam::PinholeFactor::error
double error(const Values &values) const override
Definition: PinholeFactor.h:41
gtsam::JacobianFactor
Definition: JacobianFactor.h:91
different_sigmas::values
HybridValues values
Definition: testHybridBayesNet.cpp:245
gtsam::PinholeFactor::PinholeFactor
PinholeFactor()
Definition: PinholeFactor.h:36
gtsam::PinholeFactor::Base
SmartFactorBase< PinholeCamera< Cal3Bundler > > Base
Definition: PinholeFactor.h:35
gtsam::PinholeFactor::linearize
std::shared_ptr< GaussianFactor > linearize(const Values &values) const override
Definition: PinholeFactor.h:42
PinholeCamera.h
Base class for all pinhole cameras.
gtsam::SharedNoiseModel
noiseModel::Base::shared_ptr SharedNoiseModel
Definition: NoiseModel.h:762
gtsam::SmartFactorBase
Base class for smart factors. This base class has no internal point, but it has a measurement,...
Definition: SmartFactorBase.h:51
gtsam::PinholeFactor
Definition: PinholeFactor.h:33
gtsam
traits
Definition: SFMdata.h:40
gtsam::Testable
Definition: Testable.h:152
gtsam::traits
Definition: Group.h:36
gtsam::Values
Definition: Values.h:65
Cal3Bundler.h
Calibration used by Bundler.
Pose3.h
3D Pose manifold SO(3) x R^3 and group SE(3)
gtsam::PinholeFactor::PinholeFactor
PinholeFactor(const SharedNoiseModel &sharedNoiseModel, std::optional< Pose3 > body_P_sensor={}, size_t expectedNumberCameras=10)
Definition: PinholeFactor.h:37


gtsam
Author(s):
autogenerated on Sun Dec 22 2024 04:12:43