Address comments
parent
86b9761b5b
commit
21b8365d7b
|
@ -927,6 +927,16 @@ class PinholeCamera {
|
||||||
void serialize() const;
|
void serialize() const;
|
||||||
};
|
};
|
||||||
|
|
||||||
|
// Forward declaration of PinholeCameraCalX is defined here.
|
||||||
|
#include <gtsam/geometry/SimpleCamera.h>
|
||||||
|
// Some typedefs for common camera types
|
||||||
|
// PinholeCameraCal3_S2 is the same as SimpleCamera above
|
||||||
|
typedef gtsam::PinholeCamera<gtsam::Cal3_S2> PinholeCameraCal3_S2;
|
||||||
|
typedef gtsam::PinholeCamera<gtsam::Cal3DS2> PinholeCameraCal3DS2;
|
||||||
|
typedef gtsam::PinholeCamera<gtsam::Cal3Unified> PinholeCameraCal3Unified;
|
||||||
|
typedef gtsam::PinholeCamera<gtsam::Cal3Bundler> PinholeCameraCal3Bundler;
|
||||||
|
typedef gtsam::PinholeCamera<gtsam::Cal3Fisheye> PinholeCameraCal3Fisheye;
|
||||||
|
|
||||||
#include <gtsam/geometry/PinholePose.h>
|
#include <gtsam/geometry/PinholePose.h>
|
||||||
template <CALIBRATION>
|
template <CALIBRATION>
|
||||||
class PinholePose {
|
class PinholePose {
|
||||||
|
@ -978,6 +988,12 @@ class PinholePose {
|
||||||
void serialize() const;
|
void serialize() const;
|
||||||
};
|
};
|
||||||
|
|
||||||
|
typedef gtsam::PinholePose<gtsam::Cal3_S2> PinholePoseCal3_S2;
|
||||||
|
typedef gtsam::PinholePose<gtsam::Cal3DS2> PinholePoseCal3DS2;
|
||||||
|
typedef gtsam::PinholePose<gtsam::Cal3Unified> PinholePoseCal3Unified;
|
||||||
|
typedef gtsam::PinholePose<gtsam::Cal3Bundler> PinholePoseCal3Bundler;
|
||||||
|
typedef gtsam::PinholePose<gtsam::Cal3Fisheye> PinholePoseCal3Fisheye;
|
||||||
|
|
||||||
#include <gtsam/geometry/Similarity2.h>
|
#include <gtsam/geometry/Similarity2.h>
|
||||||
class Similarity2 {
|
class Similarity2 {
|
||||||
// Standard Constructors
|
// Standard Constructors
|
||||||
|
@ -1024,22 +1040,6 @@ class Similarity3 {
|
||||||
double scale() const;
|
double scale() const;
|
||||||
};
|
};
|
||||||
|
|
||||||
// Forward declaration of PinholeCameraCalX is defined here.
|
|
||||||
#include <gtsam/geometry/SimpleCamera.h>
|
|
||||||
// Some typedefs for common camera types
|
|
||||||
// PinholeCameraCal3_S2 is the same as SimpleCamera above
|
|
||||||
typedef gtsam::PinholeCamera<gtsam::Cal3_S2> PinholeCameraCal3_S2;
|
|
||||||
typedef gtsam::PinholeCamera<gtsam::Cal3DS2> PinholeCameraCal3DS2;
|
|
||||||
typedef gtsam::PinholeCamera<gtsam::Cal3Unified> PinholeCameraCal3Unified;
|
|
||||||
typedef gtsam::PinholeCamera<gtsam::Cal3Bundler> PinholeCameraCal3Bundler;
|
|
||||||
typedef gtsam::PinholeCamera<gtsam::Cal3Fisheye> PinholeCameraCal3Fisheye;
|
|
||||||
|
|
||||||
typedef gtsam::PinholePose<gtsam::Cal3_S2> PinholePoseCal3_S2;
|
|
||||||
typedef gtsam::PinholePose<gtsam::Cal3DS2> PinholePoseCal3DS2;
|
|
||||||
typedef gtsam::PinholePose<gtsam::Cal3Unified> PinholePoseCal3Unified;
|
|
||||||
typedef gtsam::PinholePose<gtsam::Cal3Bundler> PinholePoseCal3Bundler;
|
|
||||||
typedef gtsam::PinholePose<gtsam::Cal3Fisheye> PinholePoseCal3Fisheye;
|
|
||||||
|
|
||||||
template <T>
|
template <T>
|
||||||
class CameraSet {
|
class CameraSet {
|
||||||
CameraSet();
|
CameraSet();
|
||||||
|
|
|
@ -77,10 +77,14 @@ struct GTSAM_EXPORT SfmData {
|
||||||
size_t numberCameras() const { return cameras.size(); }
|
size_t numberCameras() const { return cameras.size(); }
|
||||||
|
|
||||||
/// The track formed by series of landmark measurements
|
/// The track formed by series of landmark measurements
|
||||||
SfmTrack track(size_t idx) const { return tracks[idx]; }
|
const SfmTrack& track(size_t idx) const { return tracks[idx]; }
|
||||||
|
|
||||||
/// The camera pose at frame index `idx`
|
/// The camera pose at frame index `idx`
|
||||||
SfmCamera camera(size_t idx) const { return cameras[idx]; }
|
const SfmCamera& camera(size_t idx) const { return cameras[idx]; }
|
||||||
|
|
||||||
|
/// Getters
|
||||||
|
const std::vector<SfmCamera>& cameraList() const { return cameras; }
|
||||||
|
const std::vector<SfmTrack>& trackList() const { return tracks; }
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @brief Create projection factors using keys i and P(j)
|
* @brief Create projection factors using keys i and P(j)
|
||||||
|
|
|
@ -36,15 +36,15 @@ class SfmData {
|
||||||
static gtsam::SfmData FromBundlerFile(string filename);
|
static gtsam::SfmData FromBundlerFile(string filename);
|
||||||
static gtsam::SfmData FromBalFile(string filename);
|
static gtsam::SfmData FromBalFile(string filename);
|
||||||
|
|
||||||
std::vector<gtsam::SfmTrack> tracks;
|
std::vector<gtsam::SfmTrack>& trackList() const;
|
||||||
std::vector<gtsam::PinholeCamera<gtsam::Cal3Bundler>> cameras;
|
std::vector<gtsam::PinholeCamera<gtsam::Cal3Bundler>>& cameraList() const;
|
||||||
|
|
||||||
void addTrack(const gtsam::SfmTrack& t);
|
void addTrack(const gtsam::SfmTrack& t);
|
||||||
void addCamera(const gtsam::SfmCamera& cam);
|
void addCamera(const gtsam::SfmCamera& cam);
|
||||||
size_t numberTracks() const;
|
size_t numberTracks() const;
|
||||||
size_t numberCameras() const;
|
size_t numberCameras() const;
|
||||||
gtsam::SfmTrack track(size_t idx) const;
|
gtsam::SfmTrack& track(size_t idx) const;
|
||||||
gtsam::PinholeCamera<gtsam::Cal3Bundler> camera(size_t idx) const;
|
gtsam::PinholeCamera<gtsam::Cal3Bundler>& camera(size_t idx) const;
|
||||||
|
|
||||||
gtsam::NonlinearFactorGraph generalSfmFactors(
|
gtsam::NonlinearFactorGraph generalSfmFactors(
|
||||||
const gtsam::SharedNoiseModel& model =
|
const gtsam::SharedNoiseModel& model =
|
||||||
|
|
Loading…
Reference in New Issue