|
|
| | PinholeCamera () |
| |
| | PinholeCamera (const Pose3 &pose) |
| |
| | PinholeCamera (const Pose3 &pose, const Calibration &K) |
| |
|
| | PinholeCamera (const Vector &v) |
| | Init from vector, can be 6D (default calibration) or dim. More...
|
| |
| | PinholeCamera (const Vector &v, const Vector &K) |
| | Init from Vector and calibration. More...
|
| |
|
| bool | equals (const Base &camera, double tol=1e-9) const |
| | assert equality up to a tolerance More...
|
| |
| void | print (const std::string &s="PinholeCamera") const override |
| | print More...
|
| |
|
| | ~PinholeCamera () override |
| |
| const Pose3 & | pose () const |
| | return pose More...
|
| |
| const Pose3 & | getPose (OptionalJacobian< 6, dimension > H) const |
| | return pose, with derivative More...
|
| |
| const Calibration & | calibration () const override |
| | return calibration More...
|
| |
| | PinholeBaseK () |
| |
| | PinholeBaseK (const Pose3 &pose) |
| |
| | PinholeBaseK (const Vector &v) |
| |
| virtual | ~PinholeBaseK () |
| |
| std::pair< Point2, bool > | projectSafe (const Point3 &pw) const |
| | Project a point into the image and check depth. More...
|
| |
| 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=boost::none, OptionalJacobian< 2, 3 > Dpoint=boost::none, OptionalJacobian< 2, DimK > Dcal=boost::none) const |
| | project a 3D point from world coordinates into the image More...
|
| |
| Point2 | project (const Unit3 &pw, OptionalJacobian< 2, 6 > Dpose=boost::none, OptionalJacobian< 2, 2 > Dpoint=boost::none, OptionalJacobian< 2, DimK > Dcal=boost::none) 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=boost::none, OptionalJacobian< 3, 2 > Dresult_dp=boost::none, OptionalJacobian< 3, 1 > Dresult_ddepth=boost::none, OptionalJacobian< 3, DimK > Dresult_dcal=boost::none) 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=boost::none, OptionalJacobian< 1, 3 > Dpoint=boost::none) const |
| |
| double | range (const Pose3 &pose, OptionalJacobian< 1, 6 > Dcamera=boost::none, OptionalJacobian< 1, 6 > Dpose=boost::none) const |
| |
| double | range (const CalibratedCamera &camera, OptionalJacobian< 1, 6 > Dcamera=boost::none, OptionalJacobian< 1, 6 > Dother=boost::none) const |
| |
| double | range (const PinholeBaseK< CalibrationB > &camera, OptionalJacobian< 1, 6 > Dcamera=boost::none, OptionalJacobian< 1, 6 > Dother=boost::none) 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...
|
| |
| 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=boost::none, OptionalJacobian< 2, 3 > Dpoint=boost::none) const |
| |
| Point2 | project2 (const Unit3 &point, OptionalJacobian< 2, 6 > Dpose=boost::none, OptionalJacobian< 2, 2 > Dpoint=boost::none) const |
| |
|
|
| static PinholeCamera | Level (const Calibration &K, const Pose2 &pose2, double height) |
| |
| static PinholeCamera | Level (const Pose2 &pose2, double height) |
| | PinholeCamera::level with default calibration. More...
|
| |
| static PinholeCamera | Lookat (const Point3 &eye, const Point3 &target, const Point3 &upVector, const Calibration &K=Calibration()) |
| |
| static PinholeCamera | Create (const Pose3 &pose, const Calibration &K, OptionalJacobian< dimension, 6 > H1=boost::none, OptionalJacobian< dimension, DimK > H2=boost::none) |
| |
| static Pose3 | LevelPose (const Pose2 &pose2, double height) |
| |
| static Pose3 | LookatPose (const Point3 &eye, const Point3 &target, const Point3 &upVector) |
| |
| static std::pair< size_t, size_t > | translationInterval () |
| |
| static Point2 | Project (const Point3 &pc, OptionalJacobian< 2, 3 > Dpoint=boost::none) |
| |
| static Point2 | Project (const Unit3 &pc, OptionalJacobian< 2, 2 > Dpoint=boost::none) |
| |
| static Point3 | BackprojectFromCamera (const Point2 &p, const double depth, OptionalJacobian< 3, 2 > Dpoint=boost::none, OptionalJacobian< 3, 1 > Ddepth=boost::none) |
| | backproject a 2-dimensional point to a 3-dimensional point at given depth More...
|
| |
|
| typedef Eigen::Matrix< double, 2, DimK > | Matrix2K |
| |
| class | boost::serialization::access |
| |
| template<class POINT > |
| Point2 | _project2 (const POINT &pw, OptionalJacobian< 2, dimension > Dcamera, OptionalJacobian< 2, FixedDimension< POINT >::value > Dpoint) const |
| |
| Point2 | project2 (const Point3 &pw, OptionalJacobian< 2, dimension > Dcamera=boost::none, OptionalJacobian< 2, 3 > Dpoint=boost::none) const |
| | project a 3D point from world coordinates into the image More...
|
| |
| Point2 | project2 (const Unit3 &pw, OptionalJacobian< 2, dimension > Dcamera=boost::none, OptionalJacobian< 2, 2 > Dpoint=boost::none) const |
| | project a point at infinity from world coordinates into the image More...
|
| |
| double | range (const Point3 &point, OptionalJacobian< 1, dimension > Dcamera=boost::none, OptionalJacobian< 1, 3 > Dpoint=boost::none) const |
| |
| double | range (const Pose3 &pose, OptionalJacobian< 1, dimension > Dcamera=boost::none, OptionalJacobian< 1, 6 > Dpose=boost::none) const |
| |
| template<class CalibrationB > |
| double | range (const PinholeCamera< CalibrationB > &camera, OptionalJacobian< 1, dimension > Dcamera=boost::none, OptionalJacobian< 1, 6+CalibrationB::dimension > Dother=boost::none) const |
| |
| double | range (const CalibratedCamera &camera, OptionalJacobian< 1, dimension > Dcamera=boost::none, OptionalJacobian< 1, 6 > Dother=boost::none) const |
| |
| template<class Archive > |
| void | serialize (Archive &ar, const unsigned int) |
| |
template<typename Calibration>
class gtsam::PinholeCamera< Calibration >
Definition at line 33 of file PinholeCamera.h.