#include <InvDepthCamera3.h>
Private Attributes | |
std::shared_ptr< CALIBRATION > | k_ |
The fixed camera calibration. More... | |
Pose3 | pose_ |
The camera pose. More... | |
Standard Constructors | |
InvDepthCamera3 () | |
InvDepthCamera3 (const Pose3 &pose, const std::shared_ptr< CALIBRATION > &k) | |
Standard Interface | |
virtual | ~InvDepthCamera3 () |
Pose3 & | pose () |
return pose More... | |
const std::shared_ptr< CALIBRATION > & | calibration () const |
return calibration More... | |
void | print (const std::string &s="") const |
print More... | |
gtsam::Point2 | project (const Vector5 &pw, double rho, OptionalJacobian< 2, 6 > H1={}, OptionalJacobian< 2, 5 > H2={}, OptionalJacobian< 2, 1 > H3={}) const |
std::pair< Vector5, double > | backproject (const gtsam::Point2 &pi, const double depth) const |
static gtsam::Point3 | invDepthTo3D (const Vector5 &pw, double rho) |
A pinhole camera class that has a Pose3 and a Calibration.
Definition at line 34 of file InvDepthCamera3.h.
|
inline |
default constructor
Definition at line 45 of file InvDepthCamera3.h.
|
inline |
constructor with pose and calibration
Definition at line 48 of file InvDepthCamera3.h.
|
inlinevirtual |
Definition at line 55 of file InvDepthCamera3.h.
|
inline |
backproject a 2-dimensional point to an Inverse Depth landmark useful for point initialization
Definition at line 159 of file InvDepthCamera3.h.
|
inline |
return calibration
Definition at line 61 of file InvDepthCamera3.h.
|
inlinestatic |
Convert an inverse depth landmark to cartesian Point3
pw | first five parameters (x,y,z,theta,phi) of inv depth landmark |
inv | inverse depth |
Definition at line 75 of file InvDepthCamera3.h.
|
inline |
return pose
Definition at line 58 of file InvDepthCamera3.h.
|
inline |
Definition at line 64 of file InvDepthCamera3.h.
|
inline |
project a point from world InvDepth parameterization to the image
pw | is a point in the world coordinate |
H1 | is the jacobian w.r.t. [pose3 calibration] |
H2 | is the jacobian w.r.t. inv_depth_landmark |
Definition at line 87 of file InvDepthCamera3.h.
|
private |
The fixed camera calibration.
Definition at line 37 of file InvDepthCamera3.h.
|
private |
The camera pose.
Definition at line 36 of file InvDepthCamera3.h.