From 08e6d8860bb9d6b95e5ab9a195561d4126286181 Mon Sep 17 00:00:00 2001 From: Duy-Nguyen Ta Date: Thu, 11 Apr 2013 12:07:42 +0000 Subject: [PATCH] wrap VelocityConstraint3 --- gtsam_unstable/gtsam_unstable.h | 11 +++++++++++ 1 file changed, 11 insertions(+) diff --git a/gtsam_unstable/gtsam_unstable.h b/gtsam_unstable/gtsam_unstable.h index 1aa655ce8..adb14f25d 100644 --- a/gtsam_unstable/gtsam_unstable.h +++ b/gtsam_unstable/gtsam_unstable.h @@ -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 + +#include +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 //*************************************************************************