#include <CalibratedCamera.h>
Public Types | |
enum | { dimension = 6 } |
Public Types inherited from gtsam::PinholeBase | |
typedef Point2 | Measurement |
typedef Point2Vector | MeasurementVector |
typedef Rot3 | Rotation |
typedef Point3 | Translation |
Standard Constructors | |
CalibratedCamera () | |
default constructor More... | |
CalibratedCamera (const Pose3 &pose) | |
construct with pose More... | |
Named Constructors | |
static CalibratedCamera | Create (const Pose3 &pose, OptionalJacobian< dimension, 6 > H1={}) |
static CalibratedCamera | Level (const Pose2 &pose2, double height) |
static CalibratedCamera | Lookat (const Point3 &eye, const Point3 &target, const Point3 &upVector) |
Advanced Constructors | |
CalibratedCamera (const Vector &v) | |
construct from vector More... | |
Manifold | |
CalibratedCamera | retract (const Vector &d) const |
move a cameras pose according to d More... | |
Vector | localCoordinates (const CalibratedCamera &T2) const |
Return canonical coordinate. More... | |
void | print (const std::string &s="CalibratedCamera") const override |
print More... | |
size_t | dim () const |
static size_t | Dim () |
Transformations and measurement functions | |
Point2 | project (const Point3 &point, OptionalJacobian< 2, 6 > Dcamera={}, OptionalJacobian< 2, 3 > Dpoint={}) const |
Point3 | backproject (const Point2 &pn, double depth, OptionalJacobian< 3, 6 > Dresult_dpose={}, OptionalJacobian< 3, 2 > Dresult_dp={}, OptionalJacobian< 3, 1 > Dresult_ddepth={}) const |
backproject a 2-dimensional point to a 3-dimensional point at given depth More... | |
double | range (const Point3 &point, OptionalJacobian< 1, 6 > Dcamera={}, OptionalJacobian< 1, 3 > Dpoint={}) const |
double | range (const Pose3 &pose, OptionalJacobian< 1, 6 > Dcamera={}, OptionalJacobian< 1, 6 > Dpose={}) const |
double | range (const CalibratedCamera &camera, OptionalJacobian< 1, 6 > H1={}, OptionalJacobian< 1, 6 > H2={}) const |
Additional Inherited Members | |
Public Member Functions inherited from gtsam::PinholeBase | |
std::pair< Point2, bool > | projectSafe (const Point3 &pw) const |
Project a point into the image and check depth. More... | |
Point2 | project2 (const Point3 &point, OptionalJacobian< 2, 6 > Dpose={}, OptionalJacobian< 2, 3 > Dpoint={}) const |
Point2 | project2 (const Unit3 &point, OptionalJacobian< 2, 6 > Dpose={}, OptionalJacobian< 2, 2 > Dpoint={}) const |
PinholeBase () | |
Default constructor. More... | |
PinholeBase (const Pose3 &pose) | |
Constructor with pose. More... | |
PinholeBase (const Vector &v) | |
virtual | ~PinholeBase ()=default |
Default destructor. More... | |
bool | equals (const PinholeBase &camera, double tol=1e-9) const |
assert equality up to a tolerance More... | |
const Pose3 & | pose () const |
return pose, constant version More... | |
const Rot3 & | rotation () const |
get rotation More... | |
const Point3 & | translation () const |
get translation More... | |
const Pose3 & | getPose (OptionalJacobian< 6, 6 > H) const |
return pose, with derivative More... | |
Static Public Member Functions inherited from gtsam::PinholeBase | |
static Pose3 | LevelPose (const Pose2 &pose2, double height) |
static Pose3 | LookatPose (const Point3 &eye, const Point3 &target, const Point3 &upVector) |
static Point2 | Project (const Point3 &pc, OptionalJacobian< 2, 3 > Dpoint={}) |
static Point2 | Project (const Unit3 &pc, OptionalJacobian< 2, 2 > Dpoint={}) |
static Point3 | BackprojectFromCamera (const Point2 &p, const double depth, OptionalJacobian< 3, 2 > Dpoint={}, OptionalJacobian< 3, 1 > Ddepth={}) |
backproject a 2-dimensional point to a 3-dimensional point at given depth More... | |
static std::pair< size_t, size_t > | translationInterval () |
Static Protected Member Functions inherited from gtsam::PinholeBase | |
static Matrix26 | Dpose (const Point2 &pn, double d) |
static Matrix23 | Dpoint (const Point2 &pn, double d, const Matrix3 &Rt) |
A Calibrated camera class [R|-R't], calibration K=I. If calibration is known, it is more computationally efficient to calibrate the measurements rather than try to predict in pixels.
Definition at line 251 of file CalibratedCamera.h.
anonymous enum |
Enumerator | |
---|---|
dimension |
Definition at line 255 of file CalibratedCamera.h.
|
inline |
default constructor
Definition at line 263 of file CalibratedCamera.h.
|
inlineexplicit |
construct with pose
Definition at line 267 of file CalibratedCamera.h.
|
inlineexplicit |
construct from vector
Definition at line 307 of file CalibratedCamera.h.
|
inline |
backproject a 2-dimensional point to a 3-dimensional point at given depth
Definition at line 348 of file CalibratedCamera.h.
|
inlinestatic |
Definition at line 276 of file CalibratedCamera.h.
|
inlinestatic |
Definition at line 332 of file CalibratedCamera.h.
|
inline |
Definition at line 327 of file CalibratedCamera.h.
|
static |
Create a level camera at the given 2D pose and height
pose2 | specifies the location and viewing direction |
height | specifies the height of the camera (along the positive Z-axis) (theta 0 = looking in direction of positive X axis) |
Definition at line 177 of file CalibratedCamera.cpp.
Vector gtsam::CalibratedCamera::localCoordinates | ( | const CalibratedCamera & | T2 | ) | const |
Return canonical coordinate.
Definition at line 199 of file CalibratedCamera.cpp.
|
static |
Create a camera at the given eye position looking at a target point in the scene with the specified up direction vector.
eye | specifies the camera position |
target | the point to look at |
upVector | specifies the camera up direction vector, doesn't need to be on the image plane nor orthogonal to the viewing axis |
Definition at line 182 of file CalibratedCamera.cpp.
|
inlineoverridevirtual |
Point2 gtsam::CalibratedCamera::project | ( | const Point3 & | point, |
OptionalJacobian< 2, 6 > | Dcamera = {} , |
||
OptionalJacobian< 2, 3 > | Dpoint = {} |
||
) | const |
Definition at line 188 of file CalibratedCamera.cpp.
|
inline |
Calculate range to another camera
camera | Other camera |
Definition at line 398 of file CalibratedCamera.h.
|
inline |
Calculate range to a landmark
point | 3D location of landmark |
Definition at line 377 of file CalibratedCamera.h.
|
inline |
Calculate range to another pose
pose | Other SO(3) pose |
Definition at line 388 of file CalibratedCamera.h.
CalibratedCamera gtsam::CalibratedCamera::retract | ( | const Vector & | d | ) | const |
move a cameras pose according to d
Definition at line 194 of file CalibratedCamera.cpp.