#include <PinholePose.h>
Public Types | |
typedef CALIBRATION | CalibrationType |
![]() | |
typedef Point2 | Measurement |
typedef Point2Vector | MeasurementVector |
typedef Rot3 | Rotation |
typedef Point3 | Translation |
Static Private Attributes | |
static const int | DimK = FixedDimension<CALIBRATION>::value |
Standard Constructors | |
PinholeBaseK () | |
PinholeBaseK (const Pose3 &pose) | |
Advanced Constructors | |
PinholeBaseK (const Vector &v) | |
Standard Interface | |
virtual const CALIBRATION & | calibration () const =0 |
return calibration More... | |
Transformations and measurement functions | |
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 |
Additional Inherited Members | |
![]() | |
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... | |
virtual void | print (const std::string &s="PinholeBase") const |
print 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 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 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.
Definition at line 33 of file PinholePose.h.
typedef CALIBRATION gtsam::PinholeBaseK< CALIBRATION >::CalibrationType |
Definition at line 44 of file PinholePose.h.
|
inline |
default constructor
Definition at line 50 of file PinholePose.h.
|
inlineexplicit |
constructor with pose
Definition at line 54 of file PinholePose.h.
|
inlineexplicit |
Definition at line 62 of file PinholePose.h.
|
inline |
Templated projection of a point (possibly at infinity) from world coordinate to the image
pw | is a 3D point or a Unit3 (point at infinity) in world coordinates |
Dpose | is the Jacobian w.r.t. pose3 |
Dpoint | is the Jacobian w.r.t. point3 |
Dcal | is the Jacobian w.r.t. calibration |
Definition at line 90 of file PinholePose.h.
|
inline |
backproject a 2-dimensional point to a 3-dimensional point at given depth
Definition at line 133 of file PinholePose.h.
|
inline |
backproject a 2-dimensional point to a 3-dimensional point at infinity
Definition at line 164 of file PinholePose.h.
|
pure virtual |
return calibration
Implemented in gtsam::PinholePose< CALIBRATION >, and gtsam::PinholeCamera< Cal3Bundler >.
|
inline |
project a 3D point from world coordinates into the image
Definition at line 112 of file PinholePose.h.
|
inline |
project a point at infinity from world coordinates into the image
Definition at line 126 of file PinholePose.h.
|
inline |
Project a point into the image and check depth.
Definition at line 76 of file PinholePose.h.
|
inline |
Calculate range to a CalibratedCamera
camera | Other camera |
Definition at line 196 of file PinholePose.h.
|
inline |
Calculate range to a PinholePoseK derived class
camera | Other camera |
Definition at line 207 of file PinholePose.h.
|
inline |
Calculate range to a landmark
point | 3D location of landmark |
Definition at line 175 of file PinholePose.h.
|
inline |
Calculate range to another pose
pose | Other SO(3) pose |
Definition at line 186 of file PinholePose.h.
|
inline |
project a 3D point from world coordinates into the image
Definition at line 119 of file PinholePose.h.
|
staticprivate |
Definition at line 40 of file PinholePose.h.