#include <SphericalCamera.h>
Public Types | |
enum | { dimension = 6 } |
using | CalibrationType = EmptyCal |
using | Measurement = Unit3 |
using | MeasurementVector = std::vector< Unit3 > |
Public Member Functions | |
Matrix34 | cameraProjectionMatrix () const |
for Linear Triangulation More... | |
Vector | defaultErrorWhenTriangulatingBehindCamera () const |
for Nonlinear Triangulation More... | |
size_t | dim () const |
Vector6 | localCoordinates (const SphericalCamera &p) const |
return canonical coordinate More... | |
SphericalCamera | retract (const Vector6 &d) const |
move a cameras according to d More... | |
Static Public Member Functions | |
static size_t | Dim () |
static SphericalCamera | Identity () |
for Canonical More... | |
Protected Attributes | |
EmptyCal::shared_ptr | emptyCal_ |
Private Attributes | |
Pose3 | pose_ |
3D pose of camera More... | |
Standard Constructors | |
SphericalCamera () | |
Default constructor. More... | |
SphericalCamera (const Pose3 &pose) | |
Constructor with pose. More... | |
SphericalCamera (const Pose3 &pose, const EmptyCal::shared_ptr &cal) | |
Constructor with empty intrinsics (needed for smart factors) More... | |
Advanced Constructors | |
SphericalCamera (const Vector &v) | |
virtual | ~SphericalCamera ()=default |
Default destructor. More... | |
const EmptyCal::shared_ptr & | sharedCalibration () const |
return shared pointer to calibration More... | |
const EmptyCal & | calibration () const |
return calibration More... | |
Testable | |
bool | equals (const SphericalCamera &camera, double tol=1e-9) const |
assert equality up to a tolerance More... | |
virtual void | print (const std::string &s="SphericalCamera") const |
print More... | |
Standard Interface | |
const Pose3 & | pose () const |
return pose, constant version More... | |
const Rot3 & | rotation () const |
get rotation More... | |
const Point3 & | translation () const |
get translation More... | |
Transformations and measurement functions | |
std::pair< Unit3, bool > | projectSafe (const Point3 &pw) const |
Project a point into the image and check depth. More... | |
Unit3 | project2 (const Point3 &pw, OptionalJacobian< 2, 6 > Dpose={}, OptionalJacobian< 2, 3 > Dpoint={}) const |
Unit3 | project2 (const Unit3 &pwu, OptionalJacobian< 2, 6 > Dpose={}, OptionalJacobian< 2, 2 > Dpoint={}) const |
Point3 | backproject (const Unit3 &p, const double depth) const |
backproject a 2-dimensional point to a 3-dimensional point at given depth More... | |
Unit3 | backprojectPointAtInfinity (const Unit3 &p) const |
backproject point at infinity More... | |
Unit3 | project (const Point3 &point, OptionalJacobian< 2, 6 > Dpose={}, OptionalJacobian< 2, 3 > Dpoint={}) const |
Vector2 | reprojectionError (const Point3 &point, const Unit3 &measured, OptionalJacobian< 2, 6 > Dpose={}, OptionalJacobian< 2, 3 > Dpoint={}) const |
A spherical camera class that has a Pose3 and measures bearing vectors. The camera has an ‘Empty’ calibration and the only 6 dof are the pose
Definition at line 74 of file SphericalCamera.h.
Definition at line 80 of file SphericalCamera.h.
Definition at line 78 of file SphericalCamera.h.
using gtsam::SphericalCamera::MeasurementVector = std::vector<Unit3> |
Definition at line 79 of file SphericalCamera.h.
anonymous enum |
Enumerator | |
---|---|
dimension |
Definition at line 76 of file SphericalCamera.h.
|
inline |
Default constructor.
Definition at line 93 of file SphericalCamera.h.
|
inlineexplicit |
Constructor with pose.
Definition at line 97 of file SphericalCamera.h.
|
inlineexplicit |
Constructor with empty intrinsics (needed for smart factors)
Definition at line 101 of file SphericalCamera.h.
|
inlineexplicit |
Definition at line 108 of file SphericalCamera.h.
|
virtualdefault |
Default destructor.
backproject a 2-dimensional point to a 3-dimensional point at given depth
Definition at line 73 of file SphericalCamera.cpp.
backproject point at infinity
Definition at line 78 of file SphericalCamera.cpp.
|
inline |
return calibration
Definition at line 119 of file SphericalCamera.h.
|
inline |
for Linear Triangulation
Definition at line 210 of file SphericalCamera.h.
|
inline |
for Nonlinear Triangulation
Definition at line 215 of file SphericalCamera.h.
|
inline |
Definition at line 220 of file SphericalCamera.h.
|
inlinestatic |
Definition at line 223 of file SphericalCamera.h.
bool gtsam::SphericalCamera::equals | ( | const SphericalCamera & | camera, |
double | tol = 1e-9 |
||
) | const |
assert equality up to a tolerance
Definition at line 26 of file SphericalCamera.cpp.
|
inlinestatic |
for Canonical
Definition at line 204 of file SphericalCamera.h.
|
inline |
return canonical coordinate
Definition at line 199 of file SphericalCamera.h.
|
inline |
return pose, constant version
Definition at line 136 of file SphericalCamera.h.
|
virtual |
Definition at line 31 of file SphericalCamera.cpp.
Unit3 gtsam::SphericalCamera::project | ( | const Point3 & | point, |
OptionalJacobian< 2, 6 > | Dpose = {} , |
||
OptionalJacobian< 2, 3 > | Dpoint = {} |
||
) | const |
Project point into the image (note: there is no CheiralityException for a spherical camera)
point | 3D point in world coordinates |
Definition at line 83 of file SphericalCamera.cpp.
Unit3 gtsam::SphericalCamera::project2 | ( | const Point3 & | pw, |
OptionalJacobian< 2, 6 > | Dpose = {} , |
||
OptionalJacobian< 2, 3 > | Dpoint = {} |
||
) | const |
Project point into the image (note: there is no CheiralityException for a spherical camera)
point | 3D point in world coordinates |
Definition at line 41 of file SphericalCamera.cpp.
Unit3 gtsam::SphericalCamera::project2 | ( | const Unit3 & | pwu, |
OptionalJacobian< 2, 6 > | Dpose = {} , |
||
OptionalJacobian< 2, 2 > | Dpoint = {} |
||
) | const |
Project point into the image (note: there is no CheiralityException for a spherical camera)
point | 3D direction in world coordinates |
Definition at line 59 of file SphericalCamera.cpp.
Project a point into the image and check depth.
Definition at line 34 of file SphericalCamera.cpp.
Vector2 gtsam::SphericalCamera::reprojectionError | ( | const Point3 & | point, |
const Unit3 & | measured, | ||
OptionalJacobian< 2, 6 > | Dpose = {} , |
||
OptionalJacobian< 2, 3 > | Dpoint = {} |
||
) | const |
Compute reprojection error for a given 3D point in world coordinates
point | 3D point in world coordinates |
Definition at line 90 of file SphericalCamera.cpp.
|
inline |
move a cameras according to d
Definition at line 194 of file SphericalCamera.h.
|
inline |
get rotation
Definition at line 139 of file SphericalCamera.h.
|
inline |
return shared pointer to calibration
Definition at line 114 of file SphericalCamera.h.
|
inline |
get translation
Definition at line 142 of file SphericalCamera.h.
|
protected |
Definition at line 86 of file SphericalCamera.h.
|
private |
3D pose of camera
Definition at line 83 of file SphericalCamera.h.