Go to the documentation of this file.
27 #include <gtsam/dllexport.h>
72 r_(
Rot2::fromAngle(theta)), t_(
x,
y) {
77 r_(
Rot2::fromAngle(theta)), t_(
t) {
87 if (
T.rows() != 3 ||
T.cols() != 3) {
119 void print(
const std::string&
s =
"")
const;
147 static Vector3 Logmap(
const Pose2&
p, ChartJacobian
H = {});
153 Matrix3 AdjointMap()
const;
157 return AdjointMap()*
xi;
163 static Matrix3 adjointMap(
const Vector3&
v);
169 return adjointMap(
xi) *
y;
176 return adjointMap(
xi).transpose() *
y;
190 static inline Matrix3
wedge(
double vx,
double vy,
double w) {
199 static Matrix3 ExpmapDerivative(
const Vector3&
v);
202 static Matrix3 LogmapDerivative(
const Pose2&
v);
230 OptionalJacobian<2, 3> Dpose = {},
231 OptionalJacobian<2, 2> Dpoint = {})
const;
250 inline double x()
const {
return t_.x(); }
253 inline double y()
const {
return t_.y(); }
262 inline const Rot2&
r()
const {
return r_; }
267 *Hself = Matrix::Zero(2, 3);
268 (*Hself).block<2, 2>(0, 0) =
rotation().matrix();
275 if (Hself) *Hself << 0, 0, 1;
288 OptionalJacobian<1, 3> H1={}, OptionalJacobian<1, 2> H2={})
const;
295 Rot2 bearing(
const Pose2&
pose,
296 OptionalJacobian<1, 3> H1={}, OptionalJacobian<1, 3> H2={})
const;
304 OptionalJacobian<1, 3> H1={},
305 OptionalJacobian<1, 2> H2={})
const;
313 OptionalJacobian<1, 3> H1={},
314 OptionalJacobian<1, 3> H2={})
const;
342 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION //
344 friend class boost::serialization::access;
345 template<
class Archive>
346 void serialize(Archive & ar,
const unsigned int ) {
347 ar & BOOST_SERIALIZATION_NVP(t_);
348 ar & BOOST_SERIALIZATION_NVP(r_);
375 template <
typename T>
378 template <
typename T>
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
static const Pose3 pose(Rot3(Vector3(1, -1, -1).asDiagonal()), Point3(0, 0, 0.5))
const EIGEN_DEVICE_FUNC InverseReturnType inverse() const
static Vector3 adjoint_(const Vector3 &xi, const Vector3 &y)
Array< double, 1, 3 > e(1./3., 0.5, 2.)
Vector3 Adjoint(const Vector3 &xi) const
Apply AdjointMap to twist xi.
std::ostream & operator<<(std::ostream &os, const Dih6 &m)
static Matrix3 adjointMap_(const Vector3 &xi)
const Rot2 & rotation(OptionalJacobian< 1, 3 > Hself={}) const
rotation
const Point2 & t() const
translation
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
ofstream os("timeSchurFactors.csv")
static std::pair< size_t, size_t > translationInterval()
Double_ range(const Point2_ &p, const Point2_ &q)
Pose2_ Expmap(const Vector3_ &xi)
void print(const Matrix &A, const string &s, ostream &stream)
Pose2 operator*(const Pose2 &p2) const
compose syntactic sugar
Point3_ transformFrom(const Pose3_ &x, const Point3_ &p)
StridedVectorType vy(make_vector(y, *n, std::abs(*incy)))
Line3 transformTo(const Pose3 &wTc, const Line3 &wL, OptionalJacobian< 4, 6 > Dpose, OptionalJacobian< 4, 4 > Dline)
Both LieGroupTraits and Testable.
const Rot2 & r() const
rotation
static Pose2 Identity()
identity for group operation
Pose2(const Rot2 &r, const Point2 &t)
Map< Matrix< T, Dynamic, Dynamic, ColMajor >, 0, OuterStride<> > matrix(T *data, int rows, int cols, int stride)
double theta() const
get theta
AnnoyingScalar atan2(const AnnoyingScalar &y, const AnnoyingScalar &x)
static Vector3 adjointTranspose(const Vector3 &xi, const Vector3 &y)
const Point2 & translation(OptionalJacobian< 2, 3 > Hself={}) const
translation
Base class and basic functions for Lie types.
Pose2(double theta, const Point2 &t)
Rot3_ rotation(const Pose3_ &pose)
static std::pair< size_t, size_t > rotationInterval()
Array< int, Dynamic, 1 > v
Pose2(double x, double y, double theta)
static Vector3 adjoint(const Vector3 &xi, const Vector3 &y)
std::vector< Point2Pair > Point2Pairs
std::vector< Pose2Pair > Pose2Pairs
Point2 operator*(const Point2 &point) const
static Matrix3 wedge(double vx, double vy, double w)
static Similarity2 Align(const Point2Pairs &d_abPointPairs, const Rot2 &aRb, const Point2Pair ¢roids)
This method estimates the similarity transform from differences point pairs, given a known or estimat...
#define GTSAM_MAKE_ALIGNED_OPERATOR_NEW
void adjoint(const MatrixType &m)
Matrix wedge< Pose2 >(const Vector &xi)
std::pair< Pose2, Pose2 > Pose2Pair
StridedVectorType vx(make_vector(x, *n, std::abs(*incx)))
gtsam
Author(s):
autogenerated on Thu Dec 19 2024 04:02:26