Go to the documentation of this file.
53 OptionalJacobian<5, 2> H2 = {});
57 OptionalJacobian<5, 6>
H = {});
60 template<
typename Engine>
73 GTSAM_EXPORT
void print(
const std::string&
s =
"")
const;
143 OptionalJacobian<3, 3> Dpoint = {})
const;
151 {}, OptionalJacobian<5, 3>
HR = {})
const;
159 return E.rotate(
cRb);
183 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
185 friend class boost::serialization::access;
186 template<
class ARCHIVE>
187 void serialize(ARCHIVE & ar,
const unsigned int ) {
188 ar & BOOST_SERIALIZATION_NVP(
R_);
189 ar & BOOST_SERIALIZATION_NVP(
t_);
191 ar & boost::serialization::make_nvp(
"E11",
E_(0, 0));
192 ar & boost::serialization::make_nvp(
"E12",
E_(0, 1));
193 ar & boost::serialization::make_nvp(
"E13",
E_(0, 2));
194 ar & boost::serialization::make_nvp(
"E21",
E_(1, 0));
195 ar & boost::serialization::make_nvp(
"E22",
E_(1, 1));
196 ar & boost::serialization::make_nvp(
"E23",
E_(1, 2));
197 ar & boost::serialization::make_nvp(
"E31",
E_(2, 0));
198 ar & boost::serialization::make_nvp(
"E32",
E_(2, 1));
199 ar & boost::serialization::make_nvp(
"E33",
E_(2, 2));
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 Unit3 & direction() const
Direction.
static Rot3 Random(std::mt19937 &rng)
Array< double, 1, 3 > e(1./3., 0.5, 2.)
GTSAM_EXPORT double error(const Vector3 &vA, const Vector3 &vB, OptionalJacobian< 1, 5 > H={}) const
epipolar error, algebraic
GTSAM_EXPORT friend std::ostream & operator<<(std::ostream &os, const EssentialMatrix &E)
stream to stream
Unit3 epipole_b() const
Return epipole in image_b, as Unit3 to allow for infinity.
friend EssentialMatrix operator*(const Rot3 &cRb, const EssentialMatrix &E)
GTSAM_EXPORT void print(const std::string &s="") const
print with optional string
Both ManifoldTraits and Testable.
ofstream os("timeSchurFactors.csv")
EssentialMatrix retract(const Vector5 &xi) const
Retract delta to manifold.
Point3 unrotate(const Point3 &p, OptionalJacobian< 3, 3 > H1={}, OptionalJacobian< 3, 3 > H2={}) const
rotate point from world to rotated frame
static Vector3 Homogeneous(const Point2 &p)
Static function to convert Point2 to homogeneous coordinates.
static GTSAM_EXPORT EssentialMatrix FromRotationAndDirection(const Rot3 &aRb, const Unit3 &aTb, OptionalJacobian< 5, 3 > H1={}, OptionalJacobian< 5, 2 > H2={})
Named constructor with derivatives.
EssentialMatrix()
Default constructor.
Vector5 localCoordinates(const EssentialMatrix &other) const
Compute the coordinates in the tangent space.
GTSAM_EXPORT EssentialMatrix rotate(const Rot3 &cRb, OptionalJacobian< 5, 5 > HE={}, OptionalJacobian< 5, 3 > HR={}) const
Rot3 is a 3D rotation represented as a rotation matrix if the preprocessor symbol GTSAM_USE_QUATERNIO...
const Rot3 & rotation() const
Rotation.
EssentialMatrix(const Rot3 &aRb, const Unit3 &aTb)
Construct from rotation and translation.
Base class and basic functions for Manifold types.
TangentVector localCoordinates(const Class &g) const
localCoordinates as required by manifold concept: finds tangent vector between *this and g
Unit3 retract(const Vector2 &v, OptionalJacobian< 2, 2 > H={}) const
The retract function.
const Unit3 & epipole_a() const
Return epipole in image_a , as Unit3 to allow for infinity.
const Matrix3 & matrix() const
Return 3*3 matrix representation.
bool equals(const EssentialMatrix &other, double tol=1e-8) const
assert equality up to a tolerance
GTSAM_EXPORT Point3 transformTo(const Point3 &p, OptionalJacobian< 3, 5 > DE={}, OptionalJacobian< 3, 3 > Dpoint={}) const
takes point in world coordinates and transforms it to pose with |t|==1
virtual ~EssentialMatrix()
static EssentialMatrix Random(Engine &rng)
Random, using Rot3::Random and Unit3::Random.
Array< int, Dynamic, 1 > v
bool equals(const Unit3 &s, double tol=1e-9) const
The equals function with tolerance.
static Unit3 Random(std::mt19937 &rng)
GTSAM_EXPORT friend std::istream & operator>>(std::istream &is, EssentialMatrix &E)
stream from stream
Class retract(const TangentVector &v) const
retract as required by manifold concept: applies v at *this
constexpr static auto dimension
Represents a 3D point on a unit sphere.
Matrix3 E_
Essential matrix.
bool equals(const Rot3 &p, double tol=1e-9) const
OptionalJacobian< dimension, dimension > ChartJacobian
#define GTSAM_MAKE_ALIGNED_OPERATOR_NEW
3D Pose manifold SO(3) x R^3 and group SE(3)
Vector2 localCoordinates(const Unit3 &s) const
The local coordinates function.
static GTSAM_EXPORT EssentialMatrix FromPose3(const Pose3 &_1P2_, OptionalJacobian< 5, 6 > H={})
Named constructor converting a Pose3 with scale to EssentialMatrix (no scale)
gtsam
Author(s):
autogenerated on Sun Dec 22 2024 04:11:31