15#include <boost/optional.hpp>
16#include <boost/serialization/nvp.hpp>
30template <
class CALIBRATION>
34 boost::shared_ptr<CALIBRATION> k_;
58 inline const boost::shared_ptr<CALIBRATION>&
calibration()
const {
return k_; }
61 void print(
const std::string& s =
"")
const {
63 k_.print(
"calibration");
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;
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 {
91 double theta = pw(3), phi = pw(4);
92 gtsam::Point3 m(cos(theta)*cos(phi),sin(theta)*cos(phi),sin(phi));
97 if (!H1 && !H2 && !H3) {
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;
118 double H14 = -cos_phi*sin_theta/rho;
119 double H15 = -cos_theta*sin_phi/rho;
124 double H24 = cos_phi*cos_theta/rho;
125 double H25 = -sin_phi*sin_theta/rho;
131 double H35 = cos_phi/rho;
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();
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) <<
163 double theta = atan2(ray.y(), ray.x());
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(),
177 template<
class Archive>
178 void serialize(Archive & ar,
const unsigned int ) {
179 ar & BOOST_SERIALIZATION_NVP(pose_);
180 ar & BOOST_SERIALIZATION_NVP(k_);
typedef and functions to augment Eigen's MatrixXd
typedef and functions to augment Eigen's VectorXd
Base class for all pinhole cameras.
Global functions in a separate testing namespace.
Definition chartTesting.h:28
Vector2 Point2
As of GTSAM 4, in order to make GTSAM more lean, it is now possible to just typedef Point2 to Vector2...
Definition Point2.h:27
Vector3 Point3
As of GTSAM 4, in order to make GTSAM more lean, it is now possible to just typedef Point3 to Vector3...
Definition Point3.h:36
A pinhole camera class that has a Pose3 and a Calibration.
Definition PinholeCamera.h:33
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
A 3D pose (R,t) : (Rot3,Point3).
Definition Pose3.h:37
A pinhole camera class that has a Pose3 and a Calibration.
Definition InvDepthCamera3.h:31
const boost::shared_ptr< CALIBRATION > & calibration() const
return calibration
Definition InvDepthCamera3.h:58
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
Definition InvDepthCamera3.h:156
Pose3 & pose()
return pose
Definition InvDepthCamera3.h:55
static gtsam::Point3 invDepthTo3D(const Vector5 &pw, double rho)
Convert an inverse depth landmark to cartesian Point3.
Definition InvDepthCamera3.h:72
InvDepthCamera3()
default constructor
Definition InvDepthCamera3.h:42
friend class boost::serialization::access
Serialization function.
Definition InvDepthCamera3.h:176
void print(const std::string &s="") const
print
Definition InvDepthCamera3.h:61
InvDepthCamera3(const Pose3 &pose, const boost::shared_ptr< CALIBRATION > &k)
constructor with pose and calibration
Definition InvDepthCamera3.h:45
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
Definition InvDepthCamera3.h:84