wrap VelocityConstraint3

release/4.3a0
Duy-Nguyen Ta 2013-04-11 12:07:42 +00:00
parent 72325d673d
commit 08e6d8860b
1 changed files with 11 additions and 0 deletions

View File

@ -4,6 +4,7 @@
// specify the classes from gtsam we are using
virtual class gtsam::Value;
virtual class gtsam::LieScalar;
virtual class gtsam::Point2;
virtual class gtsam::Rot2;
virtual class gtsam::Pose2;
@ -367,6 +368,16 @@ virtual class DGroundConstraint : gtsam::NonlinearFactor {
DGroundConstraint(size_t key, Vector constraint, const gtsam::noiseModel::Base* model);
};
#include <gtsam/base/LieScalar.h>
#include <gtsam_unstable/dynamics/VelocityConstraint3.h>
virtual class VelocityConstraint3 : gtsam::NonlinearFactor {
/** Standard constructor */
VelocityConstraint3(size_t key1, size_t key2, size_t velKey, double dt);
Vector evaluateError(const gtsam::LieScalar& x1, const gtsam::LieScalar& x2, const gtsam::LieScalar& v) const;
};
//*************************************************************************
// nonlinear
//*************************************************************************