15 #include <boost/optional.hpp> 16 #include <boost/serialization/nvp.hpp> 30 template <
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);
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);
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) <<
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>
179 ar & BOOST_SERIALIZATION_NVP(pose_);
180 ar & BOOST_SERIALIZATION_NVP(k_);
void print(const std::string &s="") const
print with optional string
Pose3 pose_
The camera pose.
const boost::shared_ptr< CALIBRATION > & calibration() const
return calibration
int RealScalar int RealScalar int RealScalar * pc
std::pair< Vector5, double > backproject(const gtsam::Point2 &pi, const double depth) const
EIGEN_DEVICE_FUNC const SqrtReturnType sqrt() const
Pose3 & pose()
return pose
const Point3 & translation(OptionalJacobian< 3, 6 > Hself=boost::none) const
get translation
static const Point3 pt(1.0, 2.0, 3.0)
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
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
static gtsam::Point3 invDepthTo3D(const Vector5 &pw, double rho)
Jet< T, N > atan2(const Jet< T, N > &g, const Jet< T, N > &f)
typedef and functions to augment Eigen'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
void serialize(Archive &ar, const unsigned int)
boost::shared_ptr< CALIBRATION > k_
The fixed camera calibration.
EIGEN_DEVICE_FUNC const SinReturnType sin() const
virtual ~InvDepthCamera3()
static const CalibratedCamera camera(kDefaultPose)
void print(const std::string &s="") const
print