measurement functions and derivatives for simulated 2D robot More...
#include <gtsam/nonlinear/NonlinearFactor.h>
#include <gtsam/nonlinear/NonlinearFactorGraph.h>
#include <gtsam/geometry/Point2.h>
#include "gtsam/base/OptionalJacobian.h"
Go to the source code of this file.
Namespaces | |
gtsam | |
traits | |
simulated2D | |
Typedefs | |
typedef GenericMeasurement< Point2, Point2 > | simulated2D::Measurement |
typedef GenericOdometry< Point2 > | simulated2D::Odometry |
typedef GenericPrior< Point2 > | simulated2D::Prior |
Functions | |
Point2 | simulated2D::mea (const Point2 &x, const Point2 &l) |
measurement between landmark and pose More... | |
Point2 | simulated2D::mea (const Point2 &x, const Point2 &l, OptionalJacobian< 2, 2 > H1=OptionalNone, OptionalMatrixType H2=OptionalNone) |
measurement between landmark and pose, optionally returns derivative More... | |
Point2 | simulated2D::odo (const Point2 &x1, const Point2 &x2) |
odometry between two poses More... | |
Point2 | simulated2D::odo (const Point2 &x1, const Point2 &x2, OptionalJacobian< 2, 2 > H1=OptionalNone, OptionalJacobian< 2, 2 > H2=OptionalNone) |
odometry between two poses, optionally returns derivative More... | |
Point2 | simulated2D::prior (const Point2 &x) |
Prior on a single pose. More... | |
Point2 | simulated2D::prior (const Point2 &x, OptionalJacobian< 2, 2 > H=OptionalNone) |
Prior on a single pose, optionally returns derivative. More... | |
measurement functions and derivatives for simulated 2D robot
Definition in file simulated2D.h.