InvDepthCamera3.h
Go to the documentation of this file.
1 
12 #pragma once
13 
14 #include <cmath>
15 #include <boost/optional.hpp>
16 #include <boost/serialization/nvp.hpp>
17 #include <gtsam/base/Vector.h>
18 #include <gtsam/base/Matrix.h>
19 #include <gtsam/geometry/Point2.h>
20 #include <gtsam/geometry/Pose3.h>
22 
23 namespace gtsam {
24 
30 template <class CALIBRATION>
32 private:
34  boost::shared_ptr<CALIBRATION> k_;
35 
36 public:
37 
40 
43 
45  InvDepthCamera3(const Pose3& pose, const boost::shared_ptr<CALIBRATION>& k) :
46  pose_(pose),k_(k) {}
47 
51 
52  virtual ~InvDepthCamera3() {}
53 
55  inline Pose3& pose() { return pose_; }
56 
58  inline const boost::shared_ptr<CALIBRATION>& calibration() const { return k_; }
59 
61  void print(const std::string& s = "") const {
62  pose_.print("pose3");
63  k_.print("calibration");
64  }
65 
72  static gtsam::Point3 invDepthTo3D(const Vector5& pw, double rho) {
73  gtsam::Point3 ray_base(pw.segment(0,3));
74  double theta = pw(3), phi = pw(4);
75  gtsam::Point3 m(cos(theta)*cos(phi),sin(theta)*cos(phi),sin(phi));
76  return ray_base + m/rho;
77  }
78 
84  inline gtsam::Point2 project(const Vector5& pw,
85  double rho,
86  boost::optional<gtsam::Matrix&> H1 = boost::none,
87  boost::optional<gtsam::Matrix&> H2 = boost::none,
88  boost::optional<gtsam::Matrix&> H3 = boost::none) const {
89 
90  gtsam::Point3 ray_base(pw.segment(0,3));
91  double theta = pw(3), phi = pw(4);
92  gtsam::Point3 m(cos(theta)*cos(phi),sin(theta)*cos(phi),sin(phi));
93  const gtsam::Point3 landmark = ray_base + m/rho;
94 
96 
97  if (!H1 && !H2 && !H3) {
98  gtsam::Point2 uv= camera.project(landmark);
99  return uv;
100  }
101  else {
102  gtsam::Matrix J2;
103  gtsam::Point2 uv= camera.project(landmark,H1, J2, boost::none);
104  if (H1) {
105  *H1 = (*H1) * I_6x6;
106  }
107 
108  double cos_theta = cos(theta);
109  double sin_theta = sin(theta);
110  double cos_phi = cos(phi);
111  double sin_phi = sin(phi);
112  double rho2 = rho * rho;
113 
114  if (H2) {
115  double H11 = 1;
116  double H12 = 0;
117  double H13 = 0;
118  double H14 = -cos_phi*sin_theta/rho;
119  double H15 = -cos_theta*sin_phi/rho;
120 
121  double H21 = 0;
122  double H22 = 1;
123  double H23 = 0;
124  double H24 = cos_phi*cos_theta/rho;
125  double H25 = -sin_phi*sin_theta/rho;
126 
127  double H31 = 0;
128  double H32 = 0;
129  double H33 = 1;
130  double H34 = 0;
131  double H35 = cos_phi/rho;
132 
133  *H2 = J2 * (Matrix(3, 5) <<
134  H11, H12, H13, H14, H15,
135  H21, H22, H23, H24, H25,
136  H31, H32, H33, H34, H35).finished();
137  }
138  if(H3) {
139  double H16 = -cos_phi*cos_theta/rho2;
140  double H26 = -cos_phi*sin_theta/rho2;
141  double H36 = -sin_phi/rho2;
142  *H3 = J2 * (Matrix(3, 1) <<
143  H16,
144  H26,
145  H36).finished();
146  }
147  return uv;
148  }
149  }
150 
156  inline std::pair<Vector5, double> backproject(const gtsam::Point2& pi, const double depth) const {
157  const gtsam::Point2 pn = k_->calibrate(pi);
158  gtsam::Point3 pc(pn.x(), pn.y(), 1.0);
159  pc = pc/pc.norm();
160  gtsam::Point3 pw = pose_.transformFrom(pc);
161  const gtsam::Point3& pt = pose_.translation();
162  gtsam::Point3 ray = pw - pt;
163  double theta = atan2(ray.y(), ray.x()); // longitude
164  double phi = atan2(ray.z(), sqrt(ray.x()*ray.x()+ray.y()*ray.y()));
165  return std::make_pair((Vector5() << pt.x(),pt.y(),pt.z(), theta, phi).finished(),
166  double(1./depth));
167  }
168 
169 private:
170 
174 
177  template<class Archive>
178  void serialize(Archive & ar, const unsigned int /*version*/) {
179  ar & BOOST_SERIALIZATION_NVP(pose_);
180  ar & BOOST_SERIALIZATION_NVP(k_);
181  }
183 }; // \class InvDepthCamera
184 } // \namesapce gtsam
Matrix3f m
void print(const std::string &s="") const
print with optional string
Definition: Pose3.cpp:109
Pose3 pose_
The camera pose.
const boost::shared_ptr< CALIBRATION > & calibration() const
return calibration
int RealScalar int RealScalar int RealScalar * pc
Vector2 Point2
Definition: Point2.h:27
std::pair< Vector5, double > backproject(const gtsam::Point2 &pi, const double depth) const
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:43
EIGEN_DEVICE_FUNC const SqrtReturnType sqrt() const
Pose3 & pose()
return pose
const Point3 & translation(OptionalJacobian< 3, 6 > Hself=boost::none) const
get translation
Definition: Pose3.cpp:259
static const Point3 pt(1.0, 2.0, 3.0)
Rot2 theta
static Point3 landmark(0, 0, 5)
Base class for all pinhole cameras.
EIGEN_DEVICE_FUNC const CosReturnType cos() const
Point3 transformFrom(const Point3 &point, OptionalJacobian< 3, 6 > Hself=boost::none, OptionalJacobian< 3, 3 > Hpoint=boost::none) const
takes point in Pose coordinates and transforms it to world coordinates
Definition: Pose3.cpp:298
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
RealScalar s
static gtsam::Point3 invDepthTo3D(const Vector5 &pw, double rho)
Jet< T, N > atan2(const Jet< T, N > &g, const Jet< T, N > &f)
Definition: jet.h:556
traits
Definition: chartTesting.h:28
typedef and functions to augment Eigen&#39;s VectorXd
InvDepthCamera3(const Pose3 &pose, const boost::shared_ptr< CALIBRATION > &k)
friend class boost::serialization::access
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
Definition: PinholePose.h:118
void serialize(Archive &ar, const unsigned int)
boost::shared_ptr< CALIBRATION > k_
The fixed camera calibration.
EIGEN_DEVICE_FUNC const SinReturnType sin() const
Vector3 Point3
Definition: Point3.h:35
static const CalibratedCamera camera(kDefaultPose)
2D Point
3D Pose
void print(const std::string &s="") const
print


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:42:14