gtsam
4.0.0
gtsam
|
Public Member Functions | |
ProjectionFactorPPPC () | |
Default constructor. | |
ProjectionFactorPPPC (const Point2 &measured, const SharedNoiseModel &model, Key poseKey, Key transformKey, Key pointKey, Key calibKey) | |
Constructor TODO: Mark argument order standard (keys, measurement, parameters) More... | |
ProjectionFactorPPPC (const Point2 &measured, const SharedNoiseModel &model, Key poseKey, Key transformKey, Key pointKey, Key calibKey, bool throwCheirality, bool verboseCheirality) | |
Constructor with exception-handling flags TODO: Mark argument order standard (keys, measurement, parameters) More... | |
virtual | ~ProjectionFactorPPPC () |
Virtual destructor. | |
virtual NonlinearFactor::shared_ptr | clone () const |
void | print (const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const |
print More... | |
virtual bool | equals (const NonlinearFactor &p, double tol=1e-9) const |
equals | |
Vector | evaluateError (const Pose3 &pose, const Pose3 &transform, const Point3 &point, const CALIBRATION &K, boost::optional< Matrix & > H1=boost::none, boost::optional< Matrix & > H2=boost::none, boost::optional< Matrix & > H3=boost::none, boost::optional< Matrix & > H4=boost::none) const |
Evaluate error h(x)-z and optionally derivatives. | |
const Point2 & | measured () const |
return the measurement | |
bool | verboseCheirality () const |
return verbosity | |
bool | throwCheirality () const |
return flag for throwing cheirality exceptions | |
Public Member Functions inherited from gtsam::NoiseModelFactor4< POSE, POSE, LANDMARK, CALIBRATION > | |
NoiseModelFactor4 () | |
Default Constructor for I/O. | |
NoiseModelFactor4 (const SharedNoiseModel &noiseModel, Key j1, Key j2, Key j3, Key j4) | |
Constructor. More... | |
Key | key1 () const |
methods to retrieve keys | |
Key | key2 () const |
Key | key3 () const |
Key | key4 () const |
virtual Vector | unwhitenedError (const Values &x, boost::optional< std::vector< Matrix > & > H=boost::none) const |
Calls the 4-key specific version of evaluateError, which is pure virtual so must be implemented in the derived class. More... | |
virtual Vector | evaluateError (const X1 &, const X2 &, const X3 &, const X4 &, boost::optional< Matrix & > H1=boost::none, boost::optional< Matrix & > H2=boost::none, boost::optional< Matrix & > H3=boost::none, boost::optional< Matrix & > H4=boost::none) const=0 |
Override this method to finish implementing a 4-way factor. More... | |
Public Types | |
typedef NoiseModelFactor4< POSE, POSE, LANDMARK, CALIBRATION > | Base |
shorthand for base class type | |
typedef ProjectionFactorPPPC< POSE, LANDMARK, CALIBRATION > | This |
shorthand for this class | |
typedef boost::shared_ptr< This > | shared_ptr |
shorthand for a smart pointer to a factor | |
Public Types inherited from gtsam::NoiseModelFactor4< POSE, POSE, LANDMARK, CALIBRATION > | |
typedef POSE | X1 |
typedef POSE | X2 |
typedef LANDMARK | X3 |
typedef CALIBRATION | X4 |
Protected Attributes | |
Point2 | measured_ |
2D measurement | |
bool | throwCheirality_ |
If true, rethrows Cheirality exceptions (default: false) | |
bool | verboseCheirality_ |
If true, prints text for Cheirality exceptions (default: false) | |
Friends | |
class | boost::serialization::access |
Serialization function. | |
Additional Inherited Members | |
Protected Types inherited from gtsam::NoiseModelFactor4< POSE, POSE, LANDMARK, CALIBRATION > | |
typedef NoiseModelFactor | Base |
typedef NoiseModelFactor4< POSE, POSE, LANDMARK, CALIBRATION > | This |
|
inline |
Constructor TODO: Mark argument order standard (keys, measurement, parameters)
measured | is the 2 dimensional location of point in image (the measurement) |
model | is the standard deviation |
poseKey | is the index of the camera |
pointKey | is the index of the landmark |
K | shared pointer to the constant calibration |
|
inline |
Constructor with exception-handling flags TODO: Mark argument order standard (keys, measurement, parameters)
measured | is the 2 dimensional location of point in image (the measurement) |
model | is the standard deviation |
poseKey | is the index of the camera |
pointKey | is the index of the landmark |
K | shared pointer to the constant calibration |
throwCheirality | determines whether Cheirality exceptions are rethrown |
verboseCheirality | determines whether exceptions are printed for Cheirality |
|
inlinevirtual |
Reimplemented from gtsam::NonlinearFactor.
|
inlinevirtual |
s | optional string naming the factor |
keyFormatter | optional formatter useful for printing Symbols |
Reimplemented from gtsam::NoiseModelFactor.