Go to the documentation of this file.
84 std::vector<int> track_cam_indices;
89 std::adjacent_find(track_cam_indices.begin(), track_cam_indices.end());
90 bool all_cameras_unique = (
i == track_cam_indices.end());
91 return all_cameras_unique;
100 Eigen::MatrixX2d
m(numberMeasurements(), 2);
101 for (
size_t i = 0;
i < numberMeasurements();
i++) {
109 Eigen::VectorXi
v(numberMeasurements());
110 for (
size_t i = 0;
i < numberMeasurements();
i++) {
133 :
p(0, 0, 0), r(r),
g(
g),
b(
b) {}
154 void print(
const std::string&
s =
"")
const;
163 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
165 friend class boost::serialization::access;
166 template <
class ARCHIVE>
167 void serialize(ARCHIVE& ar,
const unsigned int ) {
168 ar& BOOST_SERIALIZATION_NVP(
p);
169 ar& BOOST_SERIALIZATION_NVP(r);
170 ar& BOOST_SERIALIZATION_NVP(
g);
171 ar& BOOST_SERIALIZATION_NVP(
b);
173 ar& BOOST_SERIALIZATION_NVP(siftIndices);
179 template <
typename T>
const SfmMeasurement & measurement(size_t idx) const
Get the measurement (camera index, Point2) at pose index idx
const SiftIndex & siftIndex(size_t idx) const
Get the SIFT feature index corresponding to the measurement at idx
void addMeasurement(size_t idx, const gtsam::Point2 &m)
Add measurement (camera_idx, Point2) to track.
Array< double, 1, 3 > e(1./3., 0.5, 2.)
std::vector< SfmTrack2d > SfmTrack2dVector
std::vector< SfmMeasurement > measurements
The 2D image projections (id,(u,v))
SfmTrack(const gtsam::Point3 &pt, float r=0, float g=0, float b=0)
static const Point3 pt(1.0, 2.0, 3.0)
Track containing 2D measurements associated with a single 3D point. Note: Equivalent to gtsam....
SfmTrack2d(const std::vector< SfmMeasurement > &measurements)
Eigen::VectorXi indexVector() const
Return the camera indices of the measurements.
SfmTrack(float r=0, float g=0, float b=0)
Point3 rgb() const
Get RGB values describing 3d point.
void print(const Matrix &A, const string &s, ostream &stream)
std::pair< size_t, size_t > SiftIndex
Sift index for SfmTrack.
const Point3 & point3() const
Get 3D point.
void g(const string &key, int i)
Eigen::MatrixX2d measurementMatrix() const
Return the measurements as a 2D matrix.
std::vector< SiftIndex > siftIndices
The feature descriptors (optional)
bool hasUniqueCameras() const
Check that no two measurements are from the same camera.
std::vector< double > measurements
Array< int, Dynamic, 1 > v
Point3 p
3D position of the point
size_t numberMeasurements() const
Total number of measurements in this track.
static Point2 measurement(323.0, 240.0)
std::pair< size_t, Point2 > SfmMeasurement
A measurement with its camera index.
gtsam
Author(s):
autogenerated on Fri Nov 1 2024 03:35:15