#include <PinholePose.h>
Public Types | |
enum | { dimension = 6 } |
Public Types inherited from gtsam::PinholeBaseK< CALIBRATION > | |
typedef CALIBRATION | CalibrationType |
Public Types inherited from gtsam::PinholeBase | |
typedef Point2 | Measurement |
typedef Point2Vector | MeasurementVector |
typedef Rot3 | Rotation |
typedef Point3 | Translation |
Private Types | |
typedef PinholeBaseK< CALIBRATION > | Base |
base class has 3D pose as private member More... | |
Private Attributes | |
std::shared_ptr< CALIBRATION > | K_ |
shared pointer to fixed calibration More... | |
Standard Constructors | |
PinholePose () | |
PinholePose (const Pose3 &pose) | |
PinholePose (const Pose3 &pose, const std::shared_ptr< CALIBRATION > &K) | |
Named Constructors | |
static PinholePose | Level (const std::shared_ptr< CALIBRATION > &K, const Pose2 &pose2, double height) |
static PinholePose | Level (const Pose2 &pose2, double height) |
PinholePose::level with default calibration. More... | |
static PinholePose | Lookat (const Point3 &eye, const Point3 &target, const Point3 &upVector, const std::shared_ptr< CALIBRATION > &K=std::make_shared< CALIBRATION >()) |
Advanced Constructors | |
PinholePose (const Vector &v) | |
Init from 6D vector. More... | |
PinholePose (const Vector &v, const Vector &K) | |
Init from Vector and calibration. More... | |
PinholePose (const Pose3 &pose, const Vector &K) | |
Testable | |
bool | equals (const Base &camera, double tol=1e-9) const |
assert equality up to a tolerance More... | |
void | print (const std::string &s="PinholePose") const override |
print More... | |
GTSAM_EXPORT friend std::ostream & | operator<< (std::ostream &os, const PinholePose &camera) |
stream operator More... | |
Standard Interface | |
~PinholePose () override | |
const std::shared_ptr< CALIBRATION > & | sharedCalibration () const |
return shared pointer to calibration More... | |
const CALIBRATION & | calibration () const override |
return calibration More... | |
Point2 | project2 (const Point3 &pw, OptionalJacobian< 2, 6 > Dpose={}, OptionalJacobian< 2, 3 > Dpoint={}) const |
Point2 | project2 (const Unit3 &pw, OptionalJacobian< 2, 6 > Dpose={}, OptionalJacobian< 2, 2 > Dpoint={}) const |
project2 version for point at infinity More... | |
Manifold | |
size_t | dim () const |
PinholePose | retract (const Vector6 &d) const |
move a cameras according to d More... | |
Vector6 | localCoordinates (const PinholePose &p) const |
return canonical coordinate More... | |
Matrix34 | cameraProjectionMatrix () const |
for Linear Triangulation More... | |
Vector | defaultErrorWhenTriangulatingBehindCamera () const |
for Nonlinear Triangulation More... | |
static size_t | Dim () |
static PinholePose | Identity () |
for Canonical More... | |
Additional Inherited Members | |
Public Member Functions inherited from gtsam::PinholeBaseK< CALIBRATION > | |
PinholeBaseK () | |
PinholeBaseK (const Pose3 &pose) | |
PinholeBaseK (const Vector &v) | |
std::pair< Point2, bool > | projectSafe (const Point3 &pw) const |
Project a point into the image and check depth. More... | |
template<class POINT > | |
Point2 | _project (const POINT &pw, OptionalJacobian< 2, 6 > Dpose, OptionalJacobian< 2, FixedDimension< POINT >::value > Dpoint, OptionalJacobian< 2, DimK > Dcal) const |
Point2 | project (const Point3 &pw, OptionalJacobian< 2, 6 > Dpose={}, OptionalJacobian< 2, 3 > Dpoint={}, OptionalJacobian< 2, DimK > Dcal={}) const |
project a 3D point from world coordinates into the image More... | |
Point2 | reprojectionError (const Point3 &pw, const Point2 &measured, OptionalJacobian< 2, 6 > Dpose={}, OptionalJacobian< 2, 3 > Dpoint={}, OptionalJacobian< 2, DimK > Dcal={}) const |
project a 3D point from world coordinates into the image More... | |
Point2 | project (const Unit3 &pw, OptionalJacobian< 2, 6 > Dpose={}, OptionalJacobian< 2, 2 > Dpoint={}, OptionalJacobian< 2, DimK > Dcal={}) const |
project a point at infinity from world coordinates into the image More... | |
Point3 | backproject (const Point2 &p, double depth, OptionalJacobian< 3, 6 > Dresult_dpose={}, OptionalJacobian< 3, 2 > Dresult_dp={}, OptionalJacobian< 3, 1 > Dresult_ddepth={}, OptionalJacobian< 3, DimK > Dresult_dcal={}) const |
backproject a 2-dimensional point to a 3-dimensional point at given depth More... | |
Unit3 | backprojectPointAtInfinity (const Point2 &p) const |
backproject a 2-dimensional point to a 3-dimensional point at infinity 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 > Dcamera={}, OptionalJacobian< 1, 6 > Dother={}) const |
template<class CalibrationB > | |
double | range (const PinholeBaseK< CalibrationB > &camera, OptionalJacobian< 1, 6 > Dcamera={}, OptionalJacobian< 1, 6 > Dother={}) const |
Public Member Functions inherited from gtsam::PinholeBase | |
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... | |
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 |
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 pinhole camera class that has a Pose3 and a fixed Calibration. Instead of using this class, one might consider calibrating the measurements and using CalibratedCamera, which would then be faster.
Definition at line 239 of file PinholePose.h.
|
private |
base class has 3D pose as private member
Definition at line 243 of file PinholePose.h.
anonymous enum |
Enumerator | |
---|---|
dimension |
Definition at line 248 of file PinholePose.h.
|
inline |
default constructor
Definition at line 256 of file PinholePose.h.
|
inlineexplicit |
constructor with pose, uses default calibration
Definition at line 260 of file PinholePose.h.
|
inline |
constructor with pose and calibration
Definition at line 265 of file PinholePose.h.
|
inlineexplicit |
Init from 6D vector.
Definition at line 310 of file PinholePose.h.
|
inline |
Init from Vector and calibration.
Definition at line 315 of file PinholePose.h.
|
inline |
Definition at line 320 of file PinholePose.h.
|
inlineoverride |
Definition at line 358 of file PinholePose.h.
|
inlineoverridevirtual |
return calibration
Implements gtsam::PinholeBaseK< CALIBRATION >.
Definition at line 367 of file PinholePose.h.
|
inline |
for Linear Triangulation
Definition at line 417 of file PinholePose.h.
|
inline |
for Nonlinear Triangulation
Definition at line 423 of file PinholePose.h.
|
inlinestatic |
Definition at line 397 of file PinholePose.h.
|
inline |
Definition at line 392 of file PinholePose.h.
|
inline |
assert equality up to a tolerance
Definition at line 329 of file PinholePose.h.
|
inlinestatic |
for Canonical
Definition at line 412 of file PinholePose.h.
|
inlinestatic |
PinholePose::level with default calibration.
Definition at line 286 of file PinholePose.h.
|
inlinestatic |
Create a level camera at the given 2D pose and height
K | the calibration |
pose2 | specifies the location and viewing direction (theta 0 = looking in direction of positive X axis) |
height | camera height |
Definition at line 280 of file PinholePose.h.
|
inline |
return canonical coordinate
Definition at line 407 of file PinholePose.h.
|
inlinestatic |
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 |
K | optional calibration parameter |
Definition at line 299 of file PinholePose.h.
|
inlineoverridevirtual |
|
inline |
project a point from world coordinate to the image, 2 derivatives only
pw | is a point in world coordinates |
Dpose | is the Jacobian w.r.t. the whole camera (really only the pose) |
Dpoint | is the Jacobian w.r.t. point3 |
Definition at line 376 of file PinholePose.h.
|
inline |
project2 version for point at infinity
Definition at line 382 of file PinholePose.h.
|
inline |
move a cameras according to d
Definition at line 402 of file PinholePose.h.
|
inline |
return shared pointer to calibration
Definition at line 362 of file PinholePose.h.
|
friend |
stream operator
Definition at line 335 of file PinholePose.h.
|
private |
shared pointer to fixed calibration
Definition at line 244 of file PinholePose.h.