commit
8bd4f2bcd8
|
@ -1850,7 +1850,7 @@ class GaussianFactorGraph {
|
|||
};
|
||||
|
||||
#include <gtsam/linear/GaussianConditional.h>
|
||||
virtual class GaussianConditional : gtsam::GaussianFactor {
|
||||
virtual class GaussianConditional : gtsam::JacobianFactor {
|
||||
//Constructors
|
||||
GaussianConditional(size_t key, Vector d, Matrix R, const gtsam::noiseModel::Diagonal* sigmas);
|
||||
GaussianConditional(size_t key, Vector d, Matrix R, size_t name1, Matrix S,
|
||||
|
|
|
@ -28,6 +28,7 @@
|
|||
#include <boost/serialization/optional.hpp>
|
||||
#include <boost/serialization/shared_ptr.hpp>
|
||||
#include <boost/serialization/singleton.hpp>
|
||||
#include <boost/serialization/version.hpp>
|
||||
|
||||
namespace gtsam {
|
||||
namespace noiseModel {
|
||||
|
|
|
@ -23,6 +23,7 @@
|
|||
|
||||
#include <boost/serialization/nvp.hpp>
|
||||
#include <boost/shared_ptr.hpp>
|
||||
#include <boost/serialization/version.hpp>
|
||||
|
||||
#include <vector>
|
||||
|
||||
|
|
Loading…
Reference in New Issue