45 inline Line3_
transformTo(
const Pose3_ &wTc,
const Line3_ &wL) {
62 inline Point3_
rotate(
const Rot3_&
x,
const Point3_&
p) {
66 inline Unit3_
rotate(
const Rot3_&
x,
const Unit3_&
p) {
70 inline Point3_
unrotate(
const Rot3_&
x,
const Point3_&
p) {
74 inline Unit3_
unrotate(
const Rot3_&
x,
const Unit3_&
p) {
96 template <
class CAMERA,
class POINT>
99 return camera.project2(p, Dcam, Dpoint);
103 template <
class CAMERA,
class POINT>
105 return Point2_(internal::project4<CAMERA, POINT>, camera_, p_);
110 template <
class CALIBRATION,
class POINT>
118 template <
class CALIBRATION,
class POINT>
121 return Point2_(internal::project6<CALIBRATION, POINT>, x, p, K);
124 template <
class CALIBRATION>
Point3_ unrotate(const Rot3_ &x, const Point3_ &p)
Point2_ project(const Point3_ &p_cam)
Expression version of PinholeBase::Project.
Give fixed size dimension of a type, fails at compile time if dynamic.
Point2_ project2(const Expression< CAMERA > &camera_, const Expression< POINT > &p_)
Point3 unrotate(const Point3 &p, OptionalJacobian< 3, 3 > H1=boost::none, OptionalJacobian< 3, 3 > H2=boost::none) const
rotate point from world to rotated frame
static Cal3_S2 K(500, 500, 0.1, 640/2, 480/2)
Expression< Point2 > Point2_
Expression< Cal3Bundler > Cal3Bundler_
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
Point3 rotate(const Point3 &p, OptionalJacobian< 3, 3 > H1=boost::none, OptionalJacobian< 3, 3 > H2=boost::none) const
Expression< Pose2 > Pose2_
Represents a 3D point on a unit sphere.
Base class for all pinhole cameras.
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
Point3 transformTo(const Point3 &point, OptionalJacobian< 3, 6 > Hself=boost::none, OptionalJacobian< 3, 3 > Hpoint=boost::none) const
takes point in world coordinates and transforms it to Pose coordinates
Point3_ transformFrom(const Pose3_ &x, const Point3_ &p)
Point2_ project3(const Pose3_ &x, const Expression< POINT > &p, const Expression< CALIBRATION > &K)
static const Pose3 pose(Rot3(Vector3(1,-1,-1).asDiagonal()), Point3(0, 0, 0.5))
Point3_ p_cam(x,&Pose3::transformTo, p)
Expression< Unit3 > Unit3_
Point2 project4(const CAMERA &camera, const POINT &p, OptionalJacobian< 2, CAMERA::dimension > Dcam, OptionalJacobian< 2, FixedDimension< POINT >::value > Dpoint)
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
Point3_ rotate(const Rot3_ &x, const Point3_ &p)
4 dimensional manifold of 3D lines
Expression< Point3 > Point3_
Expression< Cal3_S2 > Cal3_S2_
Point2_ uncalibrate(const Expression< CALIBRATION > &K, const Point2_ &xy_hat)
static Point2 Project(const Point3 &pc, OptionalJacobian< 2, 3 > Dpoint=boost::none)
Point2 project6(const Pose3 &x, const Point3 &p, const Cal3_S2 &K, OptionalJacobian< 2, 6 > Dpose, OptionalJacobian< 2, 3 > Dpoint, OptionalJacobian< 2, 5 > Dcal)
Line3 transformTo(const Pose3 &wTc, const Line3 &wL, OptionalJacobian< 4, 6 > Dpose, OptionalJacobian< 4, 4 > Dline)
Rot3 rotation(const Pose3 &pose, OptionalJacobian< 3, 6 > H)
static const CalibratedCamera camera(kDefaultPose)
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 x
Expression< Line3 > Line3_
Calibration used by Bundler.
Expression< Pose3 > Pose3_
const Rot3 & rotation(OptionalJacobian< 3, 6 > Hself=boost::none) const
get rotation
The most common 5DOF 3D->2D calibration.
GTSAM_EXPORT Point2 transformTo(const Point2 &point, OptionalJacobian< 2, 3 > Dpose=boost::none, OptionalJacobian< 2, 2 > Dpoint=boost::none) const
Point2 uncalibrate(const CAL &K, const Point2 &p, OptionalJacobian< 2, 5 > Dcal, OptionalJacobian< 2, 2 > Dp)