We read every piece of feedback, and take your input very seriously.
To see all available qualifiers, see our documentation.
1 parent 53b1ce3 commit 2e19450Copy full SHA for 2e19450
gtsam/nonlinear/nonlinear.i
@@ -725,13 +725,5 @@ virtual class BatchFixedLagSmoother : gtsam::FixedLagSmoother {
725
VALUE calculateEstimate(size_t key) const;
726
};
727
728
-#include <gtsam/nonlinear/ExtendedKalmanFilter.h>
729
-template<T = {gtsam::Point2, gtsam::Pose2, gtsam::Pose3}>
730
-class ExtendedKalmanFilter {
731
- ExtendedKalmanFilter(size_t key_initial, T x_initial, gtsam::noiseModel::Gaussian* P_initial);
732
- T predict(const gtsam::NoiseModelFactor& motionFactor);
733
- T update(const gtsam::NoiseModelFactor& measurementFactor);
734
- gtsam::JacobianFactor* Density() const;
735
-};
736
737
} // namespace gtsam
0 commit comments