#include <StereoCamera.h>
Public Types | |
enum | { dimension = 6 } |
typedef StereoPoint2 | Measurement |
typedef StereoPoint2Vector | MeasurementVector |
Public Member Functions | |
Standard Constructors | |
StereoCamera () | |
Default constructor allocates a calibration! More... | |
StereoCamera (const Pose3 &leftCamPose, const Cal3_S2Stereo::shared_ptr K) | |
Construct from pose and shared calibration. More... | |
const Cal3_S2Stereo & | calibration () const |
Return shared pointer to calibration. More... | |
Testable | |
void | print (const std::string &s="") const |
print More... | |
bool | equals (const StereoCamera &camera, double tol=1e-9) const |
equals More... | |
Standard Interface | |
const Pose3 & | pose () const |
pose More... | |
double | baseline () const |
baseline More... | |
StereoPoint2 | project (const Point3 &point) const |
Project 3D point to StereoPoint2 (uL,uR,v) More... | |
StereoPoint2 | project2 (const Point3 &point, OptionalJacobian< 3, 6 > H1={}, OptionalJacobian< 3, 3 > H2={}) const |
Point3 | backproject (const StereoPoint2 &z) const |
back-project a measurement More... | |
Point3 | backproject2 (const StereoPoint2 &z, OptionalJacobian< 3, 6 > H1={}, OptionalJacobian< 3, 3 > H2={}) const |
Deprecated | |
StereoPoint2 | project (const Point3 &point, OptionalJacobian< 3, 6 > H1, OptionalJacobian< 3, 3 > H2={}, OptionalJacobian< 3, 0 > H3={}) const |
Vector | defaultErrorWhenTriangulatingBehindCamera () const |
for Nonlinear Triangulation More... | |
Private Attributes | |
Cal3_S2Stereo::shared_ptr | K_ |
Pose3 | leftCamPose_ |
Manifold | |
size_t | dim () const |
Dimensionality of the tangent space. More... | |
StereoCamera | retract (const Vector &v) const |
Updates a with tangent space delta. More... | |
Vector6 | localCoordinates (const StereoCamera &t2) const |
Local coordinates of manifold neighborhood around current value. More... | |
static size_t | Dim () |
Dimensionality of the tangent space. More... | |
A stereo camera class, parameterize by left camera pose and stereo calibration
Definition at line 47 of file StereoCamera.h.
Some classes template on either PinholeCamera or StereoCamera, and this typedef informs those classes what "project" returns.
Definition at line 55 of file StereoCamera.h.
Definition at line 56 of file StereoCamera.h.
anonymous enum |
Enumerator | |
---|---|
dimension |
Definition at line 64 of file StereoCamera.h.
|
inline |
Default constructor allocates a calibration!
Definition at line 72 of file StereoCamera.h.
gtsam::StereoCamera::StereoCamera | ( | const Pose3 & | leftCamPose, |
const Cal3_S2Stereo::shared_ptr | K | ||
) |
Construct from pose and shared calibration.
Definition at line 26 of file StereoCamera.cpp.
Point3 gtsam::StereoCamera::backproject | ( | const StereoPoint2 & | z | ) | const |
back-project a measurement
Definition at line 92 of file StereoCamera.cpp.
Point3 gtsam::StereoCamera::backproject2 | ( | const StereoPoint2 & | z, |
OptionalJacobian< 3, 6 > | H1 = {} , |
||
OptionalJacobian< 3, 3 > | H2 = {} |
||
) | const |
Back-project the 2D point and compute optional derivatives
H1 | derivative with respect to pose |
H2 | derivative with respect to point |
Definition at line 102 of file StereoCamera.cpp.
|
inline |
baseline
Definition at line 134 of file StereoCamera.h.
|
inline |
Return shared pointer to calibration.
Definition at line 80 of file StereoCamera.h.
|
inline |
for Nonlinear Triangulation
Definition at line 174 of file StereoCamera.h.
|
inline |
Dimensionality of the tangent space.
Definition at line 105 of file StereoCamera.h.
|
inlinestatic |
Dimensionality of the tangent space.
Definition at line 110 of file StereoCamera.h.
|
inline |
equals
Definition at line 95 of file StereoCamera.h.
|
inline |
Local coordinates of manifold neighborhood around current value.
Definition at line 120 of file StereoCamera.h.
|
inline |
pose
Definition at line 129 of file StereoCamera.h.
|
inline |
Definition at line 89 of file StereoCamera.h.
StereoPoint2 gtsam::StereoCamera::project | ( | const Point3 & | point | ) | const |
Project 3D point to StereoPoint2 (uL,uR,v)
Definition at line 32 of file StereoCamera.cpp.
StereoPoint2 gtsam::StereoCamera::project | ( | const Point3 & | point, |
OptionalJacobian< 3, 6 > | H1, | ||
OptionalJacobian< 3, 3 > | H2 = {} , |
||
OptionalJacobian< 3, 0 > | H3 = {} |
||
) | const |
Project 3D point and compute optional derivatives
H1 | derivative with respect to pose |
H2 | derivative with respect to point |
H3 | IGNORED (for calibration) |
Definition at line 82 of file StereoCamera.cpp.
StereoPoint2 gtsam::StereoCamera::project2 | ( | const Point3 & | point, |
OptionalJacobian< 3, 6 > | H1 = {} , |
||
OptionalJacobian< 3, 3 > | H2 = {} |
||
) | const |
Project 3D point and compute optional derivatives
H1 | derivative with respect to pose |
H2 | derivative with respect to point |
Definition at line 37 of file StereoCamera.cpp.
|
inline |
Updates a with tangent space delta.
Definition at line 115 of file StereoCamera.h.
|
private |
Definition at line 60 of file StereoCamera.h.
|
private |
Definition at line 59 of file StereoCamera.h.