Go to the documentation of this file.
30 using namespace gtsam;
37 Values() : nrPoses_(0), nrPoints_(0) {}
51 int nrPoses()
const {
return nrPoses_; }
52 int nrPoints()
const {
return nrPoints_; }
83 template<
class VALUE = Pose2>
104 template<
class VALUE = Pose2>
111 using NoiseModelFactor2<VALUE, VALUE>::evaluateError;
131 return std::static_pointer_cast<gtsam::NonlinearFactor>(
Class between(const Class &g) const
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
std::shared_ptr< This > shared_ptr
static const Pose3 pose(Rot3(Vector3(1, -1, -1).asDiagonal()), Point3(0, 0, 0.5))
~GenericOdometry() override
gtsam::NonlinearFactor::shared_ptr clone() const override
Unary factor encoding a soft prior on a vector.
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
Vector evaluateError(const Pose2 &x, OptionalMatrixType H=OptionalNone) const
Evaluate error and optionally derivative.
Pose2 measured_
Between measurement for odometry factor.
GenericPosePrior(const Pose2 &measured, const SharedNoiseModel &model, Key key)
Create generic pose prior.
Pose2 odo(const Pose2 &x1, const Pose2 &x2)
odometry between two poses
Special class for optional Jacobian arguments.
noiseModel::Base::shared_ptr SharedNoiseModel
GenericOdometry(const Pose2 &measured, const SharedNoiseModel &model, Key i1, Key i2)
TangentVector localCoordinates(const Class &g) const
localCoordinates as required by manifold concept: finds tangent vector between *this and g
noiseModel::Diagonal::shared_ptr model
const gtsam::Symbol key('X', 0)
Non-linear factor base classes.
GenericOdometry< VALUE > This
Factor Graph consisting of non-linear factors.
GenericOdometry< Pose2 > Odometry
void insert(Key j, const Value &val)
void insertPose(Key i, const Pose2 &p)
insert a pose
Vector evaluateError(const VALUE &x1, const VALUE &x2, OptionalMatrixType H1, OptionalMatrixType H2) const override
Evaluate error and optionally derivative.
Matrix * OptionalMatrixType
Pose2 measured_
measurement
std::uint64_t Key
Integer nonlinear key type.
Graph specialization for syntactic sugar use with matlab.
Pose2 prior(const Pose2 &x)
Prior on a single pose.
Pose3 x2(Rot3::Ypr(0.0, 0.0, 0.0), l2)
A non-templated config holding any types of Manifold-group elements.
void insertPoint(Key j, const Point2 &p)
insert a landmark
gtsam
Author(s):
autogenerated on Sat Nov 16 2024 04:04:19