26 #include <gtsam/dllexport.h> 81 GTSAM_EXPORT
void print(
const std::string&
s)
const;
126 GTSAM_EXPORT
static Similarity3 Align(
const std::vector<Point3Pair>& abPointPairs);
138 GTSAM_EXPORT
static Similarity3 Align(
const std::vector<Pose3Pair>& abPosePairs);
173 GTSAM_EXPORT
static Matrix4
wedge(
const Vector7&
xi);
183 GTSAM_EXPORT
const Matrix4
matrix()
const;
202 GTSAM_EXPORT
operator Pose3()
const;
205 inline static size_t Dim() {
210 inline size_t dim()
const {
GTSAM_EXPORT bool operator==(const Similarity3 &other) const
Exact equality.
GTSAM_EXPORT const Matrix4 matrix() const
Calculate 4*4 matrix group equivalent.
static size_t Dim()
Dimensionality of tangent space = 7 DOF - used to autodetect sizes.
static GTSAM_EXPORT Vector7 Logmap(const Similarity3 &s, OptionalJacobian< 7, 7 > Hm=boost::none)
static GTSAM_EXPORT Similarity3 Expmap(const Vector7 &v, OptionalJacobian< 7, 7 > Hm=boost::none)
static GTSAM_EXPORT Similarity3 identity()
Return an identity transform.
Rot2 R(Rot2::fromAngle(0.1))
double scale() const
Return the scale.
static Vector7 Local(const Similarity3 &other, ChartJacobian H=boost::none)
static GTSAM_EXPORT Matrix4 wedge(const Vector7 &xi)
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
GTSAM_EXPORT bool equals(const Similarity3 &sim, double tol) const
Compare with tolerance.
Matrix wedge< Similarity3 >(const Vector &xi)
size_t dim() const
Dimensionality of tangent space = 7 DOF.
GTSAM_EXPORT Similarity3 operator*(const Similarity3 &S) const
Composition.
Base class and basic functions for Manifold types.
GTSAM_EXPORT Similarity3()
Default constructor.
GTSAM_EXPORT void print(const std::string &s) const
Print with optional string.
static Similarity3 Retract(const Vector7 &v, ChartJacobian H=boost::none)
const Point3 & translation() const
Return a GTSAM translation.
static GTSAM_EXPORT Similarity3 Align(const std::vector< Point3Pair > &abPointPairs)
Base class and basic functions for Lie types.
cout<< "The eigenvalues of A are:"<< endl<< ces.eigenvalues()<< endl;cout<< "The matrix of eigenvectors, V, is:"<< endl<< ces.eigenvectors()<< endl<< endl;complex< float > lambda
GTSAM_EXPORT Similarity3 inverse() const
Return the inverse.
const Rot3 & rotation() const
Return a GTSAM rotation.
ofstream os("timeSchurFactors.csv")
Both LieGroupTraits and Testable.
GTSAM_EXPORT Point3 transformFrom(const Point3 &p, OptionalJacobian< 3, 7 > H1=boost::none, OptionalJacobian< 3, 3 > H2=boost::none) const
Action on a point p is s*(R*p+t)
static Matrix3 GetV(Vector3 w, double lambda)
Calculate expmap and logmap coefficients.
GTSAM_EXPORT Matrix7 AdjointMap() const
Project from one tangent space to another.
3D rotation represented as a rotation matrix or quaternion
GTSAM_EXPORT friend std::ostream & operator<<(std::ostream &os, const Similarity3 &p)