testFactorTesting.cpp
Go to the documentation of this file.
1 /* ----------------------------------------------------------------------------
2 
3  * GTSAM Copyright 2010, Georgia Tech Research Corporation,
4  * Atlanta, Georgia 30332-0415
5  * All Rights Reserved
6  * Authors: Frank Dellaert, et al. (see THANKS for the full author list)
7 
8  * See LICENSE for the license information
9 
10  * -------------------------------1------------------------------------------- */
11 
19 #include <gtsam/geometry/Pose3.h>
22 #include <gtsam/slam/expressions.h>
23 
25 
26 using namespace gtsam;
27 
28 /* ************************************************************************* */
29 Vector3 bodyVelocity(const Pose3& w_t_b,
30  const Vector3& vec_w,
31  OptionalJacobian<3, 6> Hpose = boost::none,
32  OptionalJacobian<3, 3> Hvel = boost::none) {
33  Matrix36 Hrot__pose;
34  Rot3 w_R_b = w_t_b.rotation(Hrot__pose);
35  Matrix33 Hvel__rot;
36  Vector3 vec_b = w_R_b.unrotate(vec_w, Hvel__rot, Hvel);
37  if (Hpose) {
38  *Hpose = Hvel__rot * Hrot__pose;
39  }
40  return vec_b;
41 }
42 
43 // Functor used to create an expression for the measured wheel speed scaled
44 // by the scale factor.
46  public:
47  explicit ScaledVelocityFunctor(double measured_wheel_speed)
48  : measured_velocity_(measured_wheel_speed, 0, 0) {}
49 
50  // Computes the scaled measured velocity vector from the measured wheel speed
51  // and velocity scale factor. Also computes the corresponding jacobian
52  // (w.r.t. the velocity scale).
53  Vector3 operator()(double vscale,
54  OptionalJacobian<3, 1> H = boost::none) const {
55  // The velocity scale factor value we are optimizing for is centered around
56  // 0, so we need to add 1 to it before scaling the velocity.
57  const Vector3 scaled_velocity = (vscale + 1.0) * measured_velocity_;
58  if (H) {
59  *H = measured_velocity_;
60  }
61  return scaled_velocity;
62  }
63 
64  private:
66 };
67 
68 /* ************************************************************************* */
69 TEST(ExpressionTesting, Issue16) {
70  const double tol = 1e-4;
71  const double numerical_step = 1e-3;
72 
73  // Note: name of keys matters: if we use 'p' instead of 'x' then this no
74  // longer repros the problem from issue 16. This is because the order of
75  // evaluation in linearizeNumerically depends on the key values. To repro
76  // we want to first evaluate the jacobian for the scale, then velocity,
77  // then pose.
78  const auto pose_key = Symbol('x', 1);
79  const auto vel_key = Symbol('v', 1);
80  const auto scale_key = Symbol('s', 1);
81 
82  Values values;
83  values.insert<Pose3>(pose_key, Pose3());
84  values.insert<Vector3>(vel_key, Vector3(1, 0, 0));
85  values.insert<double>(scale_key, 0);
86 
87  const Vector3_ body_vel(&bodyVelocity,
88  Pose3_(pose_key),
89  Vector3_(vel_key));
90  const Vector3_ scaled_measured_vel(ScaledVelocityFunctor(1),
91  Double_(scale_key));
92  const auto err_expr = body_vel - scaled_measured_vel;
93 
94  const auto err = err_expr.value(values);
95  EXPECT_LONGS_EQUAL(3, err.size());
98  "ScaleAndCompare", err_expr, values, numerical_step, tol));
99 }
100 
101 /* ************************************************************************* */
102 int main() {
103  TestResult tr;
104  return TestRegistry::runAllTests(tr);
105 }
106 /* ************************************************************************* */
107 
int main()
bool testExpressionJacobians(const std::string &name_, const gtsam::Expression< T > &expression, const gtsam::Values &values, double nd_step, double tolerance)
static const Eigen::MatrixBase< Vector3 >::ConstantReturnType Z_3x1
Definition: Vector.h:46
static int runAllTests(TestResult &result)
Eigen::Vector3d Vector3
Definition: Vector.h:43
Expression< double > Double_
void insert(Key j, const Value &val)
Definition: Values.cpp:140
Point3 unrotate(const Point3 &p, OptionalJacobian< 3, 3 > H1=boost::none, OptionalJacobian< 3, 3 > H2=boost::none) const
rotate point from world to rotated frame
Definition: Rot3.cpp:136
leaf::MyValues values
Vector3 operator()(double vscale, OptionalJacobian< 3, 1 > H=boost::none) 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
Test harness methods for expressions.
#define EXPECT(condition)
Definition: Test.h:151
Array< double, 1, 3 > e(1./3., 0.5, 2.)
ScaledVelocityFunctor(double measured_wheel_speed)
traits
Definition: chartTesting.h:28
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Definition: Matrix.cpp:42
#define EXPECT_LONGS_EQUAL(expected, actual)
Definition: Test.h:155
T value(const Values &values, boost::optional< std::vector< Matrix > & > H=boost::none) const
Return value and optional derivatives, reverse AD version Notes: this is not terribly efficient...
TEST(LPInitSolver, InfiniteLoopSingleVar)
const G double tol
Definition: Group.h:83
3D Pose
Expression< Pose3 > Pose3_
Vector3 bodyVelocity(const Pose3 &w_t_b, const Vector3 &vec_w, OptionalJacobian< 3, 6 > Hpose=boost::none, OptionalJacobian< 3, 3 > Hvel=boost::none)
const Rot3 & rotation(OptionalJacobian< 3, 6 > Hself=boost::none) const
get rotation
Definition: Pose3.cpp:266
Expression< Vector3 > Vector3_


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:46:35