typo
parent
d472362614
commit
8aff7b52f0
|
@ -738,7 +738,7 @@ virtual class ProjectionFactorPPPC : gtsam::NoiseModelFactor {
|
||||||
};
|
};
|
||||||
typedef gtsam::ProjectionFactorPPPC<gtsam::Pose3, gtsam::Point3, gtsam::Cal3_S2> ProjectionFactorPPPCCal3_S2;
|
typedef gtsam::ProjectionFactorPPPC<gtsam::Pose3, gtsam::Point3, gtsam::Cal3_S2> ProjectionFactorPPPCCal3_S2;
|
||||||
typedef gtsam::ProjectionFactorPPPC<gtsam::Pose3, gtsam::Point3, gtsam::Cal3DS2> ProjectionFactorPPPCCal3DS2;
|
typedef gtsam::ProjectionFactorPPPC<gtsam::Pose3, gtsam::Point3, gtsam::Cal3DS2> ProjectionFactorPPPCCal3DS2;
|
||||||
typedef gtsam::ProjectionFactorPPPC<gtsam::Pose3, gtsam::Point3, gtsam::Cal3Fisheye> ProjectionFactorPPPCal3Fisheye;
|
typedef gtsam::ProjectionFactorPPPC<gtsam::Pose3, gtsam::Point3, gtsam::Cal3Fisheye> ProjectionFactorPPPCCal3Fisheye;
|
||||||
|
|
||||||
#include <gtsam_unstable/slam/ProjectionFactorRollingShutter.h>
|
#include <gtsam_unstable/slam/ProjectionFactorRollingShutter.h>
|
||||||
virtual class ProjectionFactorRollingShutter : gtsam::NoiseModelFactor {
|
virtual class ProjectionFactorRollingShutter : gtsam::NoiseModelFactor {
|
||||||
|
|
Loading…
Reference in New Issue