20 #include <gtsam_unstable/nonlinear/expressionTesting.h> 22 #include <type_traits> 25 using namespace gtsam;
36 typedef Eigen::Vector3d
type;
39 return (other - origin).head<2>();
42 return origin + Eigen::Vector3d(2.0 * d[0], 3.0 * d[1], 0.0);
52 template<>
struct dimension<ProjectionChart> :
public std::integral_constant<int, 2> {};
60 Eigen::Vector3d pval(1.0, 2.0, 3.0);
67 Eigen::Vector3d pstandard = point.
value(standard);
68 Eigen::Vector3d pcustom = point.
value(custom);
85 std::shared_ptr<GaussianFactor> gfstandard = f.linearize(standard);
86 std::shared_ptr<JacobianFactor> jfstandard =
89 typedef std::pair<Eigen::MatrixXd, Eigen::VectorXd> Jacobian;
93 std::shared_ptr<GaussianFactor> gfcustom = f.linearize(custom);
94 std::shared_ptr<JacobianFactor> jfcustom =
97 Eigen::MatrixXd expectedJacobian = Eigen::MatrixXd::Zero(3,2);
98 expectedJacobian(0,0) = 2.0;
99 expectedJacobian(1,1) = 3.0;
100 Jacobian Jcustom = jfcustom->jacobianUnweighted();
104 const double fd_step = 1
e-5;
105 const double tolerance = 1
e-5;
static int runAllTests(TestResult &result)
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 origin
const ValueType at(Key j) const
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
static type retract(const type &origin, const vector &d)
std::pair< Matrix, Vector > jacobianUnweighted() const
Returns (dense) A,b pair associated with factor, does not bake in weights.
static shared_ptr Create(size_t dim)
#define EXPECT_CORRECT_EXPRESSION_JACOBIANS(expression, values, numerical_derivative_step, tolerance)
Check the Jacobians produced by an expression against finite differences.
VectorValues zeroVectors() const
static vector local(const type &origin, const type &other)
#define EXPECT(condition)
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
Array< double, 1, 3 > e(1./3., 0.5, 2.)
#define EXPECT_LONGS_EQUAL(expected, actual)
Expression< Point2 > projection(f, p_cam)
T value(const Values &values, std::vector< Matrix > *H=nullptr) const
Return value and optional derivatives, reverse AD version Notes: this is not terribly efficient...
void insert(Key j, const Value &val)
TEST(SmartFactorBase, Pinhole)
static int getDimension(const type &origin)