24#include <gtsam/base/concepts.h>
27#include <gtsam/dllexport.h>
28#include <boost/serialization/nvp.hpp>
35 : CheiralityException(std::numeric_limits<Key>::max()) {}
37 CheiralityException(
Key j)
41 Key nearbyVariable()
const {
return j_;}
58 typedef Point3 Translation;
65 typedef Point2Vector MeasurementVector;
89 static Matrix23
Dpoint(
const Point2& pn,
double d,
const Matrix3& Rt);
145 virtual void print(
const std::string& s =
"PinholeBase")
const;
158 return pose_.rotation();
163 return pose_.translation();
190 std::pair<Point2, bool> projectSafe(
const Point3& pw)
const;
210 static Point3 BackprojectFromCamera(
const Point2& p,
const double depth,
224 return std::make_pair(3, 5);
232 friend class boost::serialization::access;
233 template<
class Archive>
234 void serialize(Archive & ar,
const unsigned int ) {
235 ar & BOOST_SERIALIZATION_NVP(pose_);
285 static CalibratedCamera Level(
const Pose2& pose2,
double height);
295 static CalibratedCamera Lookat(
const Point3& eye,
const Point3& target,
296 const Point3& upVector);
326 void print(
const std::string& s =
"CalibratedCamera")
const override {
331 inline size_t dim()
const {
336 inline static size_t Dim() {
358 Matrix31 Dpoint_ddepth;
360 Dresult_dp ? &Dpoint_dpn : 0,
361 Dresult_ddepth ? &Dpoint_ddepth : 0);
363 Matrix33 Dresult_dpoint;
364 const Point3 result =
pose().transformFrom(point, Dresult_dpose,
366 Dresult_dp) ? &Dresult_dpoint : 0);
369 *Dresult_dp = Dresult_dpoint * Dpoint_dpn;
371 *Dresult_ddepth = Dresult_dpoint * Dpoint_ddepth;
405 return pose().range(camera.
pose(), H1, H2);
416 friend class boost::serialization::access;
417 template<
class Archive>
418 void serialize(Archive & ar,
const unsigned int ) {
420 & boost::serialization::make_nvp(
"PinholeBase",
421 boost::serialization::base_object<PinholeBase>(*
this));
Base exception type that uses tbb_allocator if GTSAM is compiled with TBB.
Base class and basic functions for Manifold types.
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
Point2_ project(const Point3_ &p_cam)
Expression version of PinholeBase::Project.
Definition expressions.h:131
std::uint64_t Key
Integer nonlinear key type.
Definition types.h:100
A manifold defines a space in which there is a notion of a linear tangent space that can be centered ...
Definition concepts.h:30
Both ManifoldTraits and Testable.
Definition Manifold.h:120
OptionalJacobian is an Eigen::Ref like class that can take be constructed using either a fixed size o...
Definition OptionalJacobian.h:41
ThreadsafeException()
Definition ThreadsafeException.h:59
Definition BearingRange.h:40
Definition BearingRange.h:194
A pinhole camera class that has a Pose3, functions as base class for all pinhole cameras.
Definition CalibratedCamera.h:52
PinholeBase()
Default constructor.
Definition CalibratedCamera.h:123
static Matrix26 Dpose(const Point2 &pn, double d)
Calculate Jacobian with respect to pose.
Definition CalibratedCamera.cpp:27
virtual void print(const std::string &s="PinholeBase") const
print
Definition CalibratedCamera.cpp:74
PinholeBase(const Pose3 &pose)
Constructor with pose.
Definition CalibratedCamera.h:126
const Point3 & translation() const
get translation
Definition CalibratedCamera.h:162
const Rot3 & rotation() const
get rotation
Definition CalibratedCamera.h:157
Point2 Measurement
Some classes template on either PinholeCamera or StereoCamera, and this typedef informs those classes...
Definition CalibratedCamera.h:64
const Pose3 & pose() const
return pose, constant version
Definition CalibratedCamera.h:152
static Pose3 LevelPose(const Pose2 &pose2, double height)
Create a level pose at the given 2D pose and height.
Definition CalibratedCamera.cpp:49
static std::pair< size_t, size_t > translationInterval()
Return the start and end indices (inclusive) of the translation component of the exponential map para...
Definition CalibratedCamera.h:223
bool equals(const PinholeBase &camera, double tol=1e-9) const
assert equality up to a tolerance
Definition CalibratedCamera.cpp:69
static Matrix23 Dpoint(const Point2 &pn, double d, const Matrix3 &Rt)
Calculate Jacobian with respect to point.
Definition CalibratedCamera.cpp:37
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
Definition CalibratedCamera.cpp:167
Rot3 Rotation
Pose Concept requirements.
Definition CalibratedCamera.h:57
static Pose3 LookatPose(const Point3 &eye, const Point3 &target, const Point3 &upVector)
Create a camera pose at the given eye position looking at a target point in the scene with the specif...
Definition CalibratedCamera.cpp:58
virtual ~PinholeBase()=default
Default destructor.
A Calibrated camera class [R|-R't], calibration K=I.
Definition CalibratedCamera.h:247
Point3 backproject(const Point2 &pn, double depth, OptionalJacobian< 3, 6 > Dresult_dpose=boost::none, OptionalJacobian< 3, 2 > Dresult_dp=boost::none, OptionalJacobian< 3, 1 > Dresult_ddepth=boost::none) const
backproject a 2-dimensional point to a 3-dimensional point at given depth
Definition CalibratedCamera.h:352
CalibratedCamera()
default constructor
Definition CalibratedCamera.h:259
double range(const Pose3 &pose, OptionalJacobian< 1, 6 > Dcamera=boost::none, OptionalJacobian< 1, 6 > Dpose=boost::none) const
Calculate range to another pose.
Definition CalibratedCamera.h:392
size_t dim() const
Definition CalibratedCamera.h:331
CalibratedCamera(const Vector &v)
construct from vector
Definition CalibratedCamera.h:303
virtual ~CalibratedCamera()
destructor
Definition CalibratedCamera.h:312
static size_t Dim()
Definition CalibratedCamera.h:336
double range(const CalibratedCamera &camera, OptionalJacobian< 1, 6 > H1=boost::none, OptionalJacobian< 1, 6 > H2=boost::none) const
Calculate range to another camera.
Definition CalibratedCamera.h:402
void print(const std::string &s="CalibratedCamera") const override
print
Definition CalibratedCamera.h:326
double range(const Point3 &point, OptionalJacobian< 1, 6 > Dcamera=boost::none, OptionalJacobian< 1, 3 > Dpoint=boost::none) const
Calculate range to a landmark.
Definition CalibratedCamera.h:381
CalibratedCamera(const Pose3 &pose)
construct with pose
Definition CalibratedCamera.h:263
A 2D pose (Point2,Rot2).
Definition Pose2.h:36
A 3D pose (R,t) : (Rot3,Point3).
Definition Pose3.h:37
double range(const Point3 &point, OptionalJacobian< 1, 6 > Hself=boost::none, OptionalJacobian< 1, 3 > Hpoint=boost::none) const
Calculate range to a landmark.
Definition Pose3.cpp:399
Rot3 is a 3D rotation represented as a rotation matrix if the preprocessor symbol GTSAM_USE_QUATERNIO...
Definition Rot3.h:58
Represents a 3D point on a unit sphere.
Definition Unit3.h:43
A 2D pose (Point2,Rot2).
Definition Pose2.h:36