24 #include <boost/make_shared.hpp> 33 template<
typename CALIBRATION>
95 template <
class POINT>
106 Dpose ||
Dpoint ? &Dpi_pn : 0);
110 *Dpose = Dpi_pn * *
Dpose;
141 Dresult_dp ? &Dpn_dp : 0);
143 Matrix31 Dpoint_ddepth;
145 (Dresult_dp || Dresult_dcal) ? &Dpoint_dpn : 0,
146 Dresult_ddepth ? &Dpoint_ddepth : 0);
147 Matrix33 Dresult_dpoint;
151 Dresult_dcal) ? &Dresult_dpoint : 0);
153 *Dresult_dcal = Dresult_dpoint * Dpoint_dpn * Dpn_dcal;
155 *Dresult_dp = Dresult_dpoint * Dpoint_dpn * Dpn_dp;
157 *Dresult_ddepth = Dresult_dpoint * Dpoint_ddepth;
166 const Unit3 pc(pn.x(), pn.y(), 1.0);
206 template<
class CalibrationB>
216 friend class boost::serialization::access;
217 template<
class Archive>
220 & boost::serialization::make_nvp(
"PinholeBase",
221 boost::serialization::base_object<PinholeBase>(*
this));
236 template<
typename CALIBRATION>
242 boost::shared_ptr<CALIBRATION>
K_;
259 Base(pose), K_(new CALIBRATION()) {
280 return PinholePose(Base::LevelPose(pose2, height), K);
298 const Point3& upVector,
const boost::shared_ptr<CALIBRATION>&
K =
299 boost::make_shared<CALIBRATION>()) {
300 return PinholePose(Base::LookatPose(eye, target, upVector),
K);
309 Base(v), K_(new CALIBRATION()) {
314 Base(v), K_(new CALIBRATION(K)) {
319 Base(pose), K_(new CALIBRATION(K)) {
336 if (!camera.
K_) os <<
", K: none";
337 else os <<
", K: " << *camera.
K_;
343 void print(
const std::string&
s =
"PinholePose")
const override {
346 std::cout <<
"s No calibration given" << std::endl;
348 K_->print(
s +
".calibration");
405 return Base::pose().localCoordinates(p.Base::pose());
418 friend class boost::serialization::access;
419 template<
class Archive>
422 & boost::serialization::make_nvp(
"PinholeBaseK",
423 boost::serialization::base_object<Base>(*
this));
424 ar & BOOST_SERIALIZATION_NVP(K_);
432 template<
typename CALIBRATION>
434 PinholePose<CALIBRATION> > {
437 template<
typename CALIBRATION>
439 PinholePose<CALIBRATION> > {
double range(const Point3 &point, OptionalJacobian< 1, 6 > Dcamera=boost::none, OptionalJacobian< 1, 3 > Dpoint=boost::none) const
void print(const Matrix &A, const string &s, ostream &stream)
void serialize(Archive &ar, const unsigned int)
const CALIBRATION & calibration() const override
return calibration
Both ManifoldTraits and Testable.
static Point2 project(const Pose3 &pose, const Unit3 &pointAtInfinity, const Cal3_S2::shared_ptr &cal)
std::pair< Point2, bool > projectSafe(const Point3 &pw) const
Project a point into the image and check depth.
Point2 project2(const Unit3 &pw, OptionalJacobian< 2, 6 > Dpose=boost::none, OptionalJacobian< 2, 2 > Dpoint=boost::none) const
project2 version for point at infinity
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
int RealScalar int RealScalar int RealScalar * pc
PinholePose(const Vector &v, const Vector &K)
Init from Vector and calibration.
Point2 project2(const Point3 &point, OptionalJacobian< 2, 6 > Dpose=boost::none, OptionalJacobian< 2, 3 > Dpoint=boost::none) const
static PinholePose Level(const Pose2 &pose2, double height)
PinholePose::level with default calibration.
Give fixed size dimension of a type, fails at compile time if dynamic.
Point2 _project(const POINT &pw, OptionalJacobian< 2, 6 > Dpose, OptionalJacobian< 2, FixedDimension< POINT >::value > Dpoint, OptionalJacobian< 2, DimK > Dcal) const
Point2 project2(const Point3 &pw, OptionalJacobian< 2, 6 > Dpose=boost::none, OptionalJacobian< 2, 3 > Dpoint=boost::none) const
PinholePose(const Pose3 &pose)
virtual const CALIBRATION & calibration() const =0
return calibration
static Cal3_S2 K(500, 500, 0.1, 640/2, 480/2)
const Point3 & translation(OptionalJacobian< 3, 6 > Hself=boost::none) const
get translation
Point3 rotate(const Point3 &p, OptionalJacobian< 3, 3 > H1=boost::none, OptionalJacobian< 3, 3 > H2=boost::none) const
const Pose3 & pose() const
return pose, constant version
void print(const std::string &s="PinholePose") const override
print
static PinholePose Lookat(const Point3 &eye, const Point3 &target, const Point3 &upVector, const boost::shared_ptr< CALIBRATION > &K=boost::make_shared< CALIBRATION >())
static PinholePose Level(const boost::shared_ptr< CALIBRATION > &K, const Pose2 &pose2, double height)
Represents a 3D point on a unit sphere.
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_CONCEPT_MANIFOLD_TYPE(CALIBRATION)
PinholePose(const Pose3 &pose, const boost::shared_ptr< CALIBRATION > &K)
static const Pose3 pose(Rot3(Vector3(1,-1,-1).asDiagonal()), Point3(0, 0, 0.5))
double range(const Point3 &point, OptionalJacobian< 1, 6 > Hself=boost::none, OptionalJacobian< 1, 3 > Hpoint=boost::none) const
void serialize(Archive &ar, const unsigned int)
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
Array< double, 1, 3 > e(1./3., 0.5, 2.)
static Matrix23 Dpoint(const Point2 &pn, double d, const Matrix3 &Rt)
double range(const CalibratedCamera &camera, OptionalJacobian< 1, 6 > Dcamera=boost::none, OptionalJacobian< 1, 6 > Dother=boost::none) const
PinholeBaseK(const Pose3 &pose)
static Matrix26 Dpose(const Point2 &pn, double d)
Vector6 localCoordinates(const PinholePose &p) const
return canonical coordinate
PinholePose(const Vector &v)
Init from 6D vector.
Calibrated camera for which only pose is unknown.
PinholeBaseK< CALIBRATION > Base
base class has 3D pose as private member
static PinholePose identity()
for Canonical
std::pair< Point2, bool > projectSafe(const Point3 &pw) const
Project a point into the image and check depth.
double range(const Pose3 &pose, OptionalJacobian< 1, 6 > Dcamera=boost::none, OptionalJacobian< 1, 6 > Dpose=boost::none) const
ofstream os("timeSchurFactors.csv")
const boost::shared_ptr< CALIBRATION > & sharedCalibration() const
return shared pointer to calibration
friend std::ostream & operator<<(std::ostream &os, const PinholePose &camera)
stream operator
boost::shared_ptr< CALIBRATION > K_
shared pointer to fixed calibration
PinholePose(const Pose3 &pose, const Vector &K)
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
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
PinholePose retract(const Vector6 &d) const
move a cameras according to d
#define GTSAM_MAKE_ALIGNED_OPERATOR_NEW
Vector3 rpy(OptionalJacobian< 3, 3 > H=boost::none) const
The matrix class, also used for vectors and row-vectors.
Unit3 backprojectPointAtInfinity(const Point2 &p) const
backproject a 2-dimensional point to a 3-dimensional point at infinity
static const CalibratedCamera camera(kDefaultPose)
PinholeBaseK(const Vector &v)
bool equals(const Base &camera, double tol=1e-9) const
assert equality up to a tolerance
CALIBRATION CalibrationType
const Rot3 & rotation(OptionalJacobian< 3, 6 > Hself=boost::none) const
get rotation
double range(const PinholeBaseK< CalibrationB > &camera, OptionalJacobian< 1, 6 > Dcamera=boost::none, OptionalJacobian< 1, 6 > Dother=boost::none) const