24 #include <gtsam/dllexport.h> 29 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION 30 #include <boost/serialization/nvp.hpp> 44 enum { dimension = 0 };
50 inline static size_t Dim() {
return dimension; }
52 void print(
const std::string&
s)
const {
53 std::cout <<
"empty calibration: " << s << std::endl;
57 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION 58 friend class boost::serialization::access; 60 template <
class Archive>
61 void serialize(Archive& ar,
const unsigned int ) {
62 ar& boost::serialization::make_nvp(
63 "EmptyCal", boost::serialization::base_object<EmptyCal>(*
this));
76 enum { dimension = 6 };
103 : pose_(pose), emptyCal_(cal) {}
129 virtual void print(
const std::string&
s =
"SphericalCamera")
const;
152 std::pair<Unit3, bool> projectSafe(
const Point3& pw)
const;
174 Unit3 backprojectPointAtInfinity(
const Unit3& p)
const;
200 return pose().localCoordinates(p.
pose());
220 size_t dim()
const {
return 6; }
223 static size_t Dim() {
return 6; }
226 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION 228 friend class boost::serialization::access;
229 template <
class Archive>
230 void serialize(Archive& ar,
const unsigned int ) {
231 ar& BOOST_SERIALIZATION_NVP(pose_);
void print(const Matrix &A, const string &s, ostream &stream)
Point2_ project(const Point3_ &p_cam)
Expression version of PinholeBase::Project.
static SphericalCamera Identity()
for Canonical
SphericalCamera(const Pose3 &pose)
Constructor with pose.
const Point3 & translation(OptionalJacobian< 3, 6 > Hself={}) const
get translation
std::string serialize(const T &input)
serializes to a string
Point2_ project2(const Expression< CAMERA > &camera_, const Expression< POINT > &p_)
Vector6 localCoordinates(const SphericalCamera &p) const
return canonical coordinate
Pose2_ Expmap(const Vector3_ &xi)
static Pose3 Identity()
identity for group operation
EmptyCal::shared_ptr emptyCal_
Pose3 pose_
3D pose of camera
Rot3 is a 3D rotation represented as a rotation matrix if the preprocessor symbol GTSAM_USE_QUATERNIO...
static Point3 backproject(const Pose3 &pose, const Point2 &point, const double &depth)
Pose3 inverse() const
inverse transformation with derivatives
const EmptyCal::shared_ptr & sharedCalibration() const
return shared pointer to calibration
Represents a 3D point on a unit sphere.
const Rot3 & rotation() const
get rotation
SphericalCamera(const Pose3 &pose, const EmptyCal::shared_ptr &cal)
Constructor with empty intrinsics (needed for smart factors)
gtsam::enable_if_t< needs_eigen_aligned_allocator< T >::value, std::shared_ptr< T > > make_shared(Args &&... args)
SphericalCamera()
Default constructor.
Base class and basic functions for Manifold types.
Array< int, Dynamic, 1 > v
SphericalCamera(const Vector &v)
Array< double, 1, 3 > e(1./3., 0.5, 2.)
const Pose3 & pose() const
return pose, constant version
Matrix34 cameraProjectionMatrix() const
for Linear Triangulation
void print(const std::string &s) const
const EmptyCal & calibration() const
return calibration
static const Pose3 pose(Rot3(Vector3(1, -1, -1).asDiagonal()), Point3(0, 0, 0.5))
Both LieGroupTraits and Testable.
static size_t Dim()
return DOF, dimensionality of tangent space
const Rot3 & rotation(OptionalJacobian< 3, 6 > Hself={}) const
get rotation
#define GTSAM_MAKE_ALIGNED_OPERATOR_NEW
std::shared_ptr< EmptyCal > shared_ptr
Vector defaultErrorWhenTriangulatingBehindCamera() const
for Nonlinear Triangulation
The matrix class, also used for vectors and row-vectors.
static const CalibratedCamera camera(kDefaultPose)
SphericalCamera retract(const Vector6 &d) const
move a cameras according to d
std::vector< Unit3 > MeasurementVector
const Point3 & translation() const
get translation