XYZFactor.h
Go to the documentation of this file.
1 
13 #pragma once
14 
16 #include <gtsam/base/Matrix.h>
17 #include <gtsam/base/Vector.h>
18 #include <gtsam/geometry/Pose3.h>
19 
20 
21 namespace rtabmap {
22 
23 template<class VALUE>
24 class XYZFactor: public gtsam::NoiseModelFactor1<VALUE> {
25 
26 private:
27  // measurement information
28  double mx_, my_, mz_;
29 
30 public:
31 
39  gtsam::NoiseModelFactor1<VALUE>(model, poseKey), mx_(m.x()), my_(m.y()), mz_(m.z()) {}
40 
41  // error function
42  // @param p the pose in Pose
43  // @param H the optional Jacobian matrix, which use boost optional and has default null pointer
45 #if GTSAM_VERSION_NUMERIC >= 40300
46  OptionalMatrixType H = OptionalNone) const {
47 #else
48  boost::optional<gtsam::Matrix&> H = boost::none) const {
49 #endif
50  if(H)
51  {
52  p.translation(H);
53  }
54  return (gtsam::Vector3() << p.x() - mx_, p.y() - my_, p.z() - mz_).finished();
55  }
57 #if GTSAM_VERSION_NUMERIC >= 40300
58  OptionalMatrixType H = OptionalNone) const {
59 #else
60  boost::optional<gtsam::Matrix&> H = boost::none) const {
61 #endif
62  return (gtsam::Vector3() << p.x() - mx_, p.y() - my_, p.z() - mz_).finished();
63  }
64 };
65 
66 } // namespace gtsamexamples
67 
H
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
Pose3.h
rtabmap::XYZFactor::mz_
double mz_
Definition: XYZFactor.h:28
rtabmap::XYZFactor::evaluateError
gtsam::Vector evaluateError(const gtsam::Pose3 &p, boost::optional< gtsam::Matrix & > H=boost::none) const
Definition: XYZFactor.h:44
rtabmap::XYZFactor::my_
double my_
Definition: XYZFactor.h:28
y
Matrix3f y
gtsam::Vector3
Eigen::Vector3d Vector3
gtsam::Vector
Eigen::VectorXd Vector
poseKey
const gtsam::Key poseKey
VALUE
VALUE
NoiseModelFactor1
#define NoiseModelFactor1
NonlinearFactor.h
z
z
x
x
m
Matrix3f m
p
Point3_ p(2)
gtsam::SharedNoiseModel
noiseModel::Base::shared_ptr SharedNoiseModel
gtsam::Pose3
rtabmap::XYZFactor
Definition: XYZFactor.h:24
gtsam
rtabmap::XYZFactor::evaluateError
gtsam::Vector evaluateError(const gtsam::Point3 &p, boost::optional< gtsam::Matrix & > H=boost::none) const
Definition: XYZFactor.h:56
gtsam::Point3
Vector3 Point3
Eigen.Matrix< double, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor >
rtabmap::XYZFactor::XYZFactor
XYZFactor(gtsam::Key poseKey, const gtsam::Point3 m, gtsam::SharedNoiseModel model)
Definition: XYZFactor.h:38
gtsam::Key
std::uint64_t Key
rtabmap
Definition: CameraARCore.cpp:35
trace.model
model
Definition: trace.py:4
rtabmap::XYZFactor::mx_
double mx_
Definition: XYZFactor.h:28
Vector.h


rtabmap
Author(s): Mathieu Labbe
autogenerated on Thu Jul 25 2024 02:50:24