8 class gtsam::LieScalar;
9 class gtsam::LieVector;
11 class gtsam::Point2Vector;
48 void print(
string s)
const;
49 unsigned char dummyTwoVar(
unsigned char a)
const;
60 PoseRTV(
double roll,
double pitch,
double yaw,
double x,
double y,
double z,
double vx,
double vy,
double vz);
64 void print(
string s)
const;
69 Vector velocity()
const;
73 Vector vector()
const;
74 Vector translationVec()
const;
75 Vector velocityVec()
const;
100 void serializable()
const;
103 #include <gtsam_unstable/geometry/Pose3Upright.h> 108 Pose3Upright(
double x,
double y,
double z,
double theta);
111 void print(
string s)
const;
117 double theta()
const;
138 void serializable()
const;
141 #include <gtsam_unstable/geometry/BearingS2.h> 144 BearingS2(
double azimuth_double,
double elevation_double);
153 void print(
string s)
const;
160 void serializable()
const;
163 #include <gtsam_unstable/geometry/SimWall2D.h> 167 SimWall2D(
double ax,
double ay,
double bx,
double by);
169 void print(
string s)
const;
176 double length()
const;
186 #include <gtsam_unstable/geometry/SimPolygon2D.h> 188 static void seedGenerator(
size_t seed);
192 static gtsam::SimPolygon2D randomTriangle(
double side_len,
double mean_side_len,
double sigma_side_len,
194 static gtsam::SimPolygon2D randomRectangle(
double side_len,
double mean_side_len,
double sigma_side_len,
199 gtsam::Point2Vector vertices()
const;
202 void print(
string s)
const;
211 static bool nearExisting(
const gtsam::Point2Vector& S,
216 static double randomDistance(
double mu,
double sigma);
217 static double randomDistance(
double mu,
double sigma,
double min_dist);
218 static gtsam::Point2 randomBoundedPoint2(
double boundary_size,
219 const gtsam::Point2Vector& landmarks,
double min_landmark_dist);
220 static gtsam::Point2 randomBoundedPoint2(
double boundary_size,
221 const gtsam::Point2Vector& landmarks,
223 static gtsam::Point2 randomBoundedPoint2(
double boundary_size,
227 const gtsam::Point2Vector& landmarks,
237 size_t max_size()
const;
238 void resize(
size_t sz);
239 size_t capacity()
const;
241 void reserve(
size_t n);
259 size_t max_size()
const;
260 void resize(
size_t sz);
261 size_t capacity()
const;
263 void reserve(
size_t n);
282 void serializable()
const;
291 void serializable()
const;
297 BetweenFactorEM(
size_t key1,
size_t key2,
const T& relativePose,
299 double prior_inlier,
double prior_outlier);
301 BetweenFactorEM(
size_t key1,
size_t key2,
const T& relativePose,
303 double prior_inlier,
double prior_outlier,
bool flag_bump_up_near_zero_probs);
309 void set_flag_bump_up_near_zero_probs(
bool flag);
310 bool get_flag_bump_up_near_zero_probs()
const;
313 void updateNoiseModels_givenCovs(
const gtsam::Values& values, Matrix cov1, Matrix cov2, Matrix cov12);
314 Matrix get_model_inlier_cov();
315 Matrix get_model_outlier_cov();
317 void serializable()
const;
326 double prior_inlier,
double prior_outlier);
331 double prior_inlier,
double prior_outlier,
bool flag_bump_up_near_zero_probs,
bool start_with_M_step);
339 void updateNoiseModels_givenCovs(
const gtsam::Values& values, Matrix cov1, Matrix cov2, Matrix cov12);
340 Matrix get_model_inlier_cov();
341 Matrix get_model_outlier_cov();
343 void serializable()
const;
357 void serializable()
const;
364 void addRange(
size_t key,
double measuredRange);
370 #include <gtsam/sam/RangeFactor.h> 371 template<POSE, POINT>
375 void serializable()
const;
381 #include <gtsam/nonlinear/NonlinearEquality.h> 389 void serializable()
const;
392 #include <gtsam_unstable/dynamics/IMUFactor.h> 404 Vector accel()
const;
422 Vector accel()
const;
451 #include <gtsam/base/deprecated/LieScalar.h> 458 Vector
evaluateError(
const gtsam::LieScalar& x1,
const gtsam::LieScalar& x2,
const gtsam::LieScalar& v)
const;
466 Vector
evaluateError(
const gtsam::LieScalar& qk1,
const gtsam::LieScalar& qk,
const gtsam::LieScalar& v)
const;
472 PendulumFactor2(
size_t vk1,
size_t vk,
size_t qKey,
double dt,
double L,
double g);
474 Vector
evaluateError(
const gtsam::LieScalar& vk1,
const gtsam::LieScalar& vk,
const gtsam::LieScalar& q)
const;
479 PendulumFactorPk(
size_t pk,
size_t qk,
size_t qk1,
double h,
double m,
double r,
double g,
double alpha);
481 Vector
evaluateError(
const gtsam::LieScalar& pk,
const gtsam::LieScalar& qk,
const gtsam::LieScalar& qk1)
const;
486 PendulumFactorPk1(
size_t pk1,
size_t qk,
size_t qk1,
double h,
double m,
double r,
double g,
double alpha);
488 Vector
evaluateError(
const gtsam::LieScalar& pk1,
const gtsam::LieScalar& qk,
const gtsam::LieScalar& qk1)
const;
491 #include <gtsam_unstable/dynamics/SimpleHelicopter.h> 493 Reconstruction(
size_t gKey1,
size_t gKey,
size_t xiKey,
double h);
499 DiscreteEulerPoincareHelicopter(
size_t xiKey,
size_t xiKey_1,
size_t gKey,
500 double h, Matrix Inertia, Vector Fu,
double m);
525 double at(
const size_t key)
const;
530 size_t getIterations()
const;
531 size_t getNonlinearVariables()
const;
532 size_t getLinearVariables()
const;
533 double getError()
const;
538 void print(
string s)
const;
550 BatchFixedLagSmoother();
571 virtual class ConcurrentFilter {
572 void print(
string s)
const;
576 virtual class ConcurrentSmoother {
577 void print(
string s)
const;
586 size_t getIterations()
const;
587 size_t getLambdas()
const;
588 size_t getNonlinearVariables()
const;
589 size_t getLinearVariables()
const;
590 double getError()
const;
611 size_t getIterations()
const;
612 size_t getLambdas()
const;
613 size_t getNonlinearVariables()
const;
614 size_t getLinearVariables()
const;
615 double getError()
const;
638 RelativeElevationFactor();
639 RelativeElevationFactor(
size_t poseKey,
size_t pointKey,
double measured,
648 DummyFactor(
size_t key1,
size_t dim1,
size_t key2,
size_t dim2);
670 #include <gtsam_unstable/slam/Mechanization_bRn2.h> 671 class Mechanization_bRn2 {
675 Vector
b_g(
double g_e);
685 #include <gtsam_unstable/slam/AHRS.h> 687 AHRS(Matrix U, Matrix F,
double g_e);
688 pair<gtsam::Mechanization_bRn2, gtsam::GaussianDensity*> initialize(
double g_e);
723 template<POSE, LANDMARK, CALIBRATION>
726 size_t poseKey,
size_t transformKey,
size_t pointKey,
const CALIBRATION* k);
737 void serialize()
const;
744 template<POSE, LANDMARK, CALIBRATION>
747 size_t poseKey,
size_t transformKey,
size_t pointKey,
size_t calibKey);
757 void serialize()
const;
An iSAM2-based fixed-lag smoother.
Derived from ProjectionFactor, but estimates body-camera transform and calibration in addition to bod...
Values calculateEstimate() const
Compute the current best estimate of all variables and return a full Values structure.
Definition: ConcurrentBatchSmoother.h:91
A simple factor that can be used to trick gtsam solvers into believing a graph is connected.
virtual void print(const std::string &s="Concurrent Filter:\n", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const =0
Implement a standard 'print' function.
Inverse Depth Factor based on Civera09tro, Montiel06rss.
noiseModel::Base is the abstract base class for all noise models.
Definition: NoiseModel.h:51
Mechanization_bRn2 correct(const Vector9 &dx) const
Correct AHRS full state given error state dx.
Definition: Mechanization_bRn2.cpp:68
PendulumFactorPk1()
default constructor to allow for serialization
Definition: Pendulum.h:179
A non-templated config holding any types of Manifold-group elements.
Definition: Values.h:70
A convenient base class for creating your own NoiseModelFactor with 2 variables.
Definition: NonlinearFactor.h:345
const Values & getLinearizationPoint() const
Access the current linearization point.
Definition: ConcurrentBatchFilter.h:81
Mechanization_bRn2 integrate(const Vector3 &u, const double dt) const
Integrate to get new state.
Definition: Mechanization_bRn2.cpp:81
Vector evaluateError(const double &x1, const double &x2, const double &v, boost::optional< Matrix & > H1=boost::none, boost::optional< Matrix & > H2=boost::none, boost::optional< Matrix & > H3=boost::none) const
x1 + v*dt - x2 = 0, with optional derivatives
Definition: VelocityConstraint3.h:39
The interface for the 'Filter' portion of the Concurrent Filtering and Smoother architecture.
Definition: ConcurrentFilteringAndSmoothing.h:39
Definition: gtsam_unstable.h:142
Point2 triangulate(const Values &x) const
Triangulate a point from at least three pose-range pairs Checks for best pair that includes first poi...
Definition: SmartRangeFactor.h:91
Definition: gtsam_unstable.h:610
TransformBtwRobotsUnaryFactor()
default constructor - only use for serialization
Definition: TransformBtwRobotsUnaryFactor.h:67
const T & measured() const
return the measurement
Definition: ExpressionFactor.h:67
This is the base class for any type to be stored in Values.
Definition: Value.h:36
DRollPrior(Key key, double wx, const gtsam::SharedNoiseModel &model)
allows for explicit roll parameterization - uses canonical coordinate
Definition: DynamicsPriors.h:37
const Point2 & measured() const
return the measurement
Definition: ProjectionFactorPPP.h:154
DeltaFactor(Key i, Key j, const Point2 &measured, const SharedNoiseModel &model)
Constructor.
Definition: TSAMFactors.h:42
Robot state for use with IMU measurements.
Definition: PoseRTV.h:23
OdometryFactorBase(Key b1, Key i, Key b2, Key j, const Pose2 &measured, const SharedNoiseModel &model)
Constructor.
Definition: TSAMFactors.h:126
Definition: RangeFactor.h:35
A Gaussian density.
Definition: GaussianDensity.h:33
Definition: gtsam_unstable.h:509
IncrementalFixedLagSmoother(double smootherLag=0.0, const ISAM2Params ¶meters=ISAM2Params())
default constructor
Definition: IncrementalFixedLagSmoother.h:41
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:57
bool verboseCheirality() const
return verbosity
Definition: ProjectionFactorPPP.h:164
double smootherLag() const
read the current smoother lag
Definition: FixedLagSmoother.h:78
Definition: FixedLagSmoother.h:33
PendulumFactor2()
default constructor to allow for serialization
Definition: Pendulum.h:76
Definition: gtsam_unstable.h:585
Template to create a binary predicate.
Definition: Testable.h:110
Definition: Mechanization_bRn2.h:17
std::pair< Mechanization_bRn2, KalmanFilter::State > aid(const Mechanization_bRn2 &mech, KalmanFilter::State state, const Vector &f, bool Farrell=0) const
Aid the AHRS with an accelerometer reading, typically called when isAidingAvailable == true.
Definition: AHRS.cpp:159
const VectorValues & getDelta() const
Access the current set of deltas to the linearization point.
Definition: ConcurrentBatchSmoother.h:84
Dummy class for testing MATLAB memory allocation.
virtual bool equals(const FixedLagSmoother &rhs, double tol=1e-9) const
Check if two IncrementalFixedLagSmoother Objects are equal.
Definition: FixedLagSmoother.cpp:40
DGroundConstraint(Key key, double height, const gtsam::SharedNoiseModel &model)
Primary constructor allows for variable height of the "floor".
Definition: DynamicsPriors.h:76
SmartRangeFactor()
Default constructor: don't use directly.
Definition: SmartRangeFactor.h:47
A Levenberg-Marquardt Batch Smoother that implements the Concurrent Filtering and Smoother interface.
Definition: ConcurrentBatchSmoother.h:31
Inverse Depth Factor based on Civera09tro, Montiel06rss.
const Point3 & referencePoint() const
return the calibration object
Definition: InvDepthFactorVariant2.h:135
A Linear Factor Graph is a factor graph where all factors are Gaussian, i.e.
Definition: GaussianFactorGraph.h:65
A Levenberg-Marquardt Batch Filter that implements the Concurrent Filtering and Smoother interface.
Definition: ConcurrentBatchFilter.h:31
A simple 3-way factor constraining double poses and velocity.
void addRange(Key key, double measuredRange)
Add a range measurement to a pose with given key.
Definition: SmartRangeFactor.h:62
NonlinearEquality()
default constructor - only for serialization
Definition: NonlinearEquality.h:77
InvDepthFactorVariant1()
Default constructor.
Definition: InvDepthFactorVariant1.h:44
ProjectionFactorPPPC()
Default constructor.
Definition: ProjectionFactorPPPC.h:55
Gaussian implements the mathematical model |R*x|^2 = |y|^2 with R'*R=inv(Sigma) where y = whiten(x) =...
Definition: NoiseModel.h:141
An abstract virtual base class for JacobianFactor and HessianFactor.
Definition: GaussianFactor.h:38
Pose3 with translational velocity.
const VectorValues & getDelta() const
Access the current set of deltas to the linearization point.
Definition: ConcurrentBatchFilter.h:91
const KeyTimestampMap & timestamps() const
Access the current set of timestamps associated with each variable.
Definition: FixedLagSmoother.h:88
Base class for a fixed-lag smoother.
BetweenFactor()
default constructor - only use for serialization
Definition: BetweenFactor.h:55
DummyFactor()
Default constructor: don't use directly.
Definition: DummyFactor.h:27
Vector evaluateError(const double &vk1, const double &vk, const double &q, boost::optional< Matrix & > H1=boost::none, boost::optional< Matrix & > H2=boost::none, boost::optional< Matrix & > H3=boost::none) const
v_k - h*g/L*sin(q) - v_k1 = 0, with optional derivatives
Definition: Pendulum.h:96
Factor to express an IMU measurement between dynamic poses.
Definition: ProjectionFactorPPP.h:34
A convenient base class for creating your own NoiseModelFactor with 4 variables.
Definition: NonlinearFactor.h:497
Definition: ISAM2Params.h:135
bool throwCheirality() const
return flag for throwing cheirality exceptions
Definition: ProjectionFactorPPP.h:167
const LevenbergMarquardtParams & params() const
read the current set of optimizer parameters
Definition: BatchFixedLagSmoother.h:76
double measured() const
return the measured
Definition: RelativeElevationFactor.h:55
A Levenberg-Marquardt Batch Smoother that implements the Concurrent Filtering and Smoothing interface...
virtual void print(const std::string &s="Concurrent Smoother:\n", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const =0
Implement a standard 'print' function.
Definition: gtsam_unstable.h:187
Definition: FastList.h:38
const ISAM2Params & params() const
return the current set of iSAM2 parameters
Definition: IncrementalFixedLagSmoother.h:89
Nonlinear factor base class.
Definition: NonlinearFactor.h:50
double range(const PoseRTV &other, OptionalJacobian< 1, 9 > H1=boost::none, OptionalJacobian< 1, 9 > H2=boost::none) const
range between translations
Definition: PoseRTV.cpp:169
DeltaFactorBase(Key b1, Key i, Key b2, Key j, const Point2 &measured, const SharedNoiseModel &model)
Constructor.
Definition: TSAMFactors.h:71
Definition: gtsam_unstable.h:104
Point3 translationIntegration(const Rot3 &r2, const Velocity3 &v2, double dt) const
predict measurement and where Point3 for x2 should be, as a way of enforcing a velocity constraint Th...
Definition: PoseRTV.cpp:161
const SharedNoiseModel & noiseModel() const
access to the noise model
Definition: NonlinearFactor.h:210
const Values & getLinearizationPoint() const
Access the current linearization point.
Definition: ConcurrentBatchSmoother.h:74
Key key1() const
methods to retrieve both keys
Definition: NonlinearFactor.h:377
virtual Result update(const NonlinearFactorGraph &newFactors=NonlinearFactorGraph(), const Values &newTheta=Values(), const KeyTimestampMap ×tamps=KeyTimestampMap(), const FastVector< size_t > &factorsToRemove=FastVector< size_t >())=0
Add new factors, updating the solution and relinearizing as needed.
Mechanization_bRn2(const Rot3 &initial_bRn=Rot3(), const Vector3 &initial_x_g=Z_3x1, const Vector3 &initial_x_a=Z_3x1)
Constructor.
Definition: Mechanization_bRn2.h:32
Unary factor for determining transformation between given trajectories of two robots.
This class represents a collection of vector-valued variables associated each with a unique integer i...
Definition: VectorValues.h:73
Vector evaluateError(const Vector6 &xik, const Vector6 &xik_1, const Pose3 &gk, boost::optional< Matrix & > H1=boost::none, boost::optional< Matrix & > H2=boost::none, boost::optional< Matrix & > H3=boost::none) const
DEP, with optional derivatives pk - pk_1 - h_*Fu_ - h_*f_ext = 0 where pk = CT_TLN(h*xi_k)*Inertia*xi...
Definition: SimpleHelicopter.h:110
Parameters for Levenberg-Marquardt optimization.
Definition: LevenbergMarquardtParams.h:33
virtual void print(const std::string &s="FixedLagSmoother:\n", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const
Print the factor for debugging and testing (implementing Testable)
Definition: FixedLagSmoother.cpp:34
void setValAValB(const Values &valA, const Values &valB)
implement functions needed to derive from Factor
Definition: TransformBtwRobotsUnaryFactorEM.h:137
Definition: gtsam_unstable.h:529
Three-way factors for the pendulum dynamics as in [Stern06siggraph] for (1) explicit Euler method,...
A convenient base class for creating your own NoiseModelFactor with 3 variables.
Definition: NonlinearFactor.h:420
Definition: gtsam_unstable.h:255
virtual bool equals(const ConcurrentSmoother &rhs, double tol=1e-9) const =0
Check if two Concurrent Smoothers are equal.
The interface for the 'Smoother' portion of the Concurrent Filtering and Smoother architecture.
Definition: ConcurrentFilteringAndSmoothing.h:99
A nonlinear sum-of-squares factor with a zero-mean noise model implementing the density Templated on...
Definition: NonlinearFactor.h:161
Definition: gtsam_unstable.h:164
FastVector< Key > KeyVector
Define collection type once and for all - also used in wrappers.
Definition: Key.h:56
virtual bool equals(const ConcurrentFilter &rhs, double tol=1e-9) const =0
Check if two Concurrent Smoothers are equal.
InvDepthFactorVariant2()
Default constructor.
Definition: InvDepthFactorVariant2.h:46
Vector3 b_g(double g_e) const
gravity in the body frame
Definition: Mechanization_bRn2.h:43
ProjectionFactorPPP()
Default constructor.
Definition: ProjectionFactorPPP.h:57
void setValAValB(const gtsam::Values &valA, const gtsam::Values &valB)
implement functions needed to derive from Factor
Definition: TransformBtwRobotsUnaryFactor.h:114
Values calculateEstimate() const
Compute an estimate from the incomplete linear delta computed during the last update.
Definition: BatchFixedLagSmoother.h:59
PoseRTV planarDynamics(double vel_rate, double heading_rate, double max_accel, double dt) const
Dynamics integrator for ground robots Always move from time 1 to time 2.
Definition: PoseRTV.cpp:60
PoseRTV flyingDynamics(double pitch_rate, double heading_rate, double lift_control, double dt) const
Simulates flying robot with simple flight model Integrates state x1 -> x2 given controls x1 = {p1,...
Definition: PoseRTV.cpp:85
Priors to be used with dynamic systems (Specifically PoseRTV)
A non-linear factor graph is a graph of non-Gaussian, i.e.
Definition: NonlinearFactorGraph.h:77
const Ordering & getOrdering() const
Access the current ordering.
Definition: ConcurrentBatchSmoother.h:79
const NonlinearFactorGraph & getFactors() const
Access the current set of factors.
Definition: ConcurrentBatchFilter.h:76
Vector evaluateError(const double &pk1, const double &qk, const double &qk1, boost::optional< Matrix & > H1=boost::none, boost::optional< Matrix & > H2=boost::none, boost::optional< Matrix & > H3=boost::none) const
1/h mr^2 (qk1-qk) - mgrh a sin((1-a)pk + a*pk1) - pk1 = 0, with optional derivatives
Definition: Pendulum.h:203
A Gaussian factor in the squared-error form.
Definition: JacobianFactor.h:87
Definition: gtsam_unstable.h:514
static Mechanization_bRn2 initialize(const Matrix &U, const Matrix &F, const double g_e=0, bool flat=false)
Matrix version of initialize.
Definition: Mechanization_bRn2.cpp:23
virtual Values calculateEstimate() const =0
Compute an estimate from the incomplete linear delta computed during the last update.
Vector evaluateError(const double &qk1, const double &qk, const double &v, boost::optional< Matrix & > H1=boost::none, boost::optional< Matrix & > H2=boost::none, boost::optional< Matrix & > H3=boost::none) const
q_k + h*v - q_k1 = 0, with optional derivatives
Definition: Pendulum.h:48
Definition: gtsam_unstable.h:233
Vector6 imuPrediction(const PoseRTV &x2, double dt) const
Dynamics predictor for both ground and flying robots, given states at 1 and 2 Always move from time 1...
Definition: PoseRTV.cpp:133
TSAM 1 Factors, simpler than the hierarchical TSAM 2.
Base classes for the 'filter' and 'smoother' portion of the Concurrent Filtering and Smoothing archit...
PriorFactor()
default constructor - only use for serialization
Definition: PriorFactor.h:51
bool throwCheirality() const
return flag for throwing cheirality exceptions
Definition: ProjectionFactorPPPC.h:158
A Levenberg-Marquardt Batch Filter that implements the Concurrent Filtering and Smoothing interface.
const NonlinearFactorGraph & getFactors() const
Access the current set of factors.
Definition: ConcurrentBatchSmoother.h:69
PendulumFactor1()
default constructor to allow for serialization
Definition: Pendulum.h:30
RangeFactor()
default constructor
Definition: RangeFactor.h:42
Factor representing a known relative altitude in global frame.
Global functions in a separate testing namespace.
Definition: chartTesting.h:28
Key key1() const
methods to retrieve keys
Definition: NonlinearFactor.h:454
Vector translationIntegrationVec(const PoseRTV &x2, double dt) const
Definition: PoseRTV.h:128
InvDepthFactorVariant3b()
Default constructor.
Definition: InvDepthFactorVariant3.h:164
IMUFactor(const Vector3 &accel, const Vector3 &gyro, double dt, const Key &key1, const Key &key2, const SharedNoiseModel &model)
time between measurements
Definition: IMUFactor.h:35
Calibration of a camera with radial distortion, calculations in base class Cal3DS2_Base.
Derived from ProjectionFactor, but estimates body-camera transform in addition to body pose and 3D la...
const Point2 & measured() const
return the measurement
Definition: ProjectionFactorPPPC.h:150
Matrix trans(const Matrix &A)
static transpose function, just calls Eigen transpose member function
Definition: Matrix.h:244
Unary factor for determining transformation between given trajectories of two robots.
AHRS(const Matrix &stationaryU, const Matrix &stationaryF, double g_e, bool flat=false)
AHRS constructor.
Definition: AHRS.cpp:24
A smart factor for range-only SLAM that does initialization and marginalization.
An LM-based fixed-lag smoother.
PoseRTV generalDynamics(const Vector &accel, const Vector &gyro, double dt) const
General Dynamics update - supply control inputs in body frame.
Definition: PoseRTV.cpp:118
Inverse Depth Factor based on Civera09tro, Montiel06rss.
Definition: Ordering.h:34
const Ordering & getOrdering() const
Access the current ordering.
Definition: ConcurrentBatchFilter.h:86
const boost::shared_ptr< CALIBRATION > calibration() const
return the calibration object
Definition: ProjectionFactorPPP.h:159
FullIMUFactor(const Vector3 &accel, const Vector3 &gyro, double dt, const Key &key1, const Key &key2, const SharedNoiseModel &model)
time between measurements
Definition: FullIMUFactor.h:37
Definition: ProjectionFactorPPPC.h:34
Vector evaluateError(const double &pk, const double &qk, const double &qk1, boost::optional< Matrix & > H1=boost::none, boost::optional< Matrix & > H2=boost::none, boost::optional< Matrix & > H3=boost::none) const
1/h mr^2 (qk1-qk)+mgrh (1-a) sin((1-a)pk + a*pk1) - pk = 0, with optional derivatives
Definition: Pendulum.h:147
bool verboseCheirality() const
return verbosity
Definition: ProjectionFactorPPPC.h:155
PoseRTV transformed_from(const Pose3 &trans, ChartJacobian Dglobal=boost::none, OptionalJacobian< 9, 6 > Dtrans=boost::none) const
Apply transform to this pose, with optional derivatives equivalent to: local = trans....
Definition: PoseRTV.cpp:182
Values calculateEstimate() const
Compute the current best estimate of all variables and return a full Values structure.
Definition: ConcurrentBatchFilter.h:98
VelocityConstraint3()
default constructor to allow for serialization
Definition: VelocityConstraint3.h:20
A Gaussian factor using the canonical parameters (information form)
Definition: HessianFactor.h:101
InvDepthFactorVariant3a()
Default constructor.
Definition: InvDepthFactorVariant3.h:44
PendulumFactorPk()
default constructor to allow for serialization
Definition: Pendulum.h:123
TransformBtwRobotsUnaryFactorEM()
default constructor - only use for serialization
Definition: TransformBtwRobotsUnaryFactorEM.h:78