27 #include <gtsam/dllexport.h> 28 #include <boost/serialization/nvp.hpp> 81 static Matrix26 Dpose(
const Point2& pn,
double d);
89 static Matrix23 Dpoint(
const Point2& pn,
double d,
const Matrix3& Rt);
145 virtual void print(
const std::string&
s =
"PinholeBase")
const;
190 std::pair<Point2, bool> projectSafe(
const Point3& pw)
const;
224 return std::make_pair(3, 5);
232 friend class boost::serialization::access;
233 template<
class Archive>
235 ar & BOOST_SERIALIZATION_NVP(pose_);
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;
366 Dresult_dp) ? &Dresult_dpoint : 0);
369 *Dresult_dp = Dresult_dpoint * Dpoint_dpn;
371 *Dresult_ddepth = Dresult_dpoint * Dpoint_ddepth;
384 return pose().range(point, Dcamera, Dpoint);
394 return this->
pose().range(pose, Dcamera, Dpose);
405 return pose().range(camera.
pose(), H1, H2);
416 friend class boost::serialization::access;
417 template<
class Archive>
420 & boost::serialization::make_nvp(
"PinholeBase",
421 boost::serialization::base_object<PinholeBase>(*
this));
435 template <
typename T>
PinholeBase(const Pose3 &pose)
Constructor with pose.
void print(const Matrix &A, const string &s, ostream &stream)
Both ManifoldTraits and Testable.
Point2_ project(const Point3_ &p_cam)
Expression version of PinholeBase::Project.
static std::pair< size_t, size_t > translationInterval()
static Point3 BackprojectFromCamera(const CalibratedCamera &camera, const Point2 &point, const double &depth)
virtual ~CalibratedCamera()
destructor
virtual void print(const std::string &s="PinholeBase") const
print
int RealScalar int RealScalar int RealScalar * pc
double range(const Pose3 &pose, OptionalJacobian< 1, 6 > Dcamera=boost::none, OptionalJacobian< 1, 6 > Dpose=boost::none) const
double range(const CalibratedCamera &camera, OptionalJacobian< 1, 6 > H1=boost::none, OptionalJacobian< 1, 6 > H2=boost::none) const
Point2_ project2(const Expression< CAMERA > &camera_, const Expression< POINT > &p_)
Pose2_ Expmap(const Vector3_ &xi)
Pose2 T2(M_PI/2.0, Point2(0.0, 2.0))
Pose3 pose_
3D pose of camera
const Point3 & translation(OptionalJacobian< 3, 6 > Hself=boost::none) const
get translation
PinholeBase()
Default constructor.
set noclip points set clip one set noclip two set bar set border lt lw set xdata set ydata set zdata set x2data set y2data set boxwidth set dummy y set format x g set format y g set format x2 g set format y2 g set format z g set angles radians set nogrid set key title set key left top Right noreverse box linetype linewidth samplen spacing width set nolabel set noarrow set nologscale set logscale x set set pointsize set encoding default set nopolar set noparametric set set set set surface set nocontour set clabel set mapping cartesian set nohidden3d set cntrparam order set cntrparam linear set cntrparam levels auto set cntrparam points set size set set xzeroaxis lt lw set x2zeroaxis lt lw set yzeroaxis lt lw set y2zeroaxis lt lw set tics in set ticslevel set tics set mxtics default set mytics default set mx2tics default set my2tics default set xtics border mirror norotate autofreq set ytics border mirror norotate autofreq set ztics border nomirror norotate autofreq set nox2tics set noy2tics set timestamp bottom norotate set rrange[*:*] noreverse nowriteback set trange[*:*] noreverse nowriteback set urange[*:*] noreverse nowriteback set vrange[*:*] noreverse nowriteback set xlabel matrix size set x2label set timefmt d m y n H
const Pose3 & pose() const
return pose, constant version
const Rot3 & rotation() const
get rotation
Key nearbyVariable() const
Represents a 3D point on a unit sphere.
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
void print(const std::string &s="CalibratedCamera") const override
print
CalibratedCamera(const Pose3 &pose)
construct with pose
static const Pose3 pose(Rot3(Vector3(1,-1,-1).asDiagonal()), Point3(0, 0, 0.5))
std::vector< Point2, Eigen::aligned_allocator< Point2 > > Point2Vector
Base class and basic functions for Manifold types.
Base exception type that uses tbb_allocator if GTSAM is compiled with TBB.
double range(const Point3 &point, OptionalJacobian< 1, 6 > Dcamera=boost::none, OptionalJacobian< 1, 3 > Dpoint=boost::none) const
Array< double, 1, 3 > e(1./3., 0.5, 2.)
CalibratedCamera(const Vector &v)
construct from vector
PinholeBase(const Vector &v)
static CalibratedCamera Create(const Pose3 &pose, OptionalJacobian< dimension, 6 > H1=boost::none)
CalibratedCamera()
default constructor
void serialize(Archive &ar, const unsigned int)
Point2(* Project)(const Point3 &, OptionalJacobian< 2, 3 >)
CheiralityException(Key j)
void serialize(Archive &ar, const unsigned int)
Point2Vector MeasurementVector
static const CalibratedCamera camera(kDefaultPose)
const Point3 & translation() const
get translation
std::uint64_t Key
Integer nonlinear key type.
const Rot3 & rotation(OptionalJacobian< 3, 6 > Hself=boost::none) const
get rotation