template<class CALIBRATION>
class gtsam::InvDepthCamera3< CALIBRATION >
A pinhole camera class that has a Pose3 and a Calibration.
|
|
Pose3 & | pose () |
| | return pose
|
|
const boost::shared_ptr< CALIBRATION > & | calibration () const |
| | return calibration
|
|
void | print (const std::string &s="") const |
| | print
|
| gtsam::Point2 | project (const Vector5 &pw, double rho, boost::optional< gtsam::Matrix & > H1=boost::none, boost::optional< gtsam::Matrix & > H2=boost::none, boost::optional< gtsam::Matrix & > H3=boost::none) const |
| | project a point from world InvDepth parameterization to the image
|
|
std::pair< Vector5, double > | backproject (const gtsam::Point2 &pi, const double depth) const |
| | backproject a 2-dimensional point to an Inverse Depth landmark useful for point initialization
|
| static gtsam::Point3 | invDepthTo3D (const Vector5 &pw, double rho) |
| | Convert an inverse depth landmark to cartesian Point3.
|