update interface files for correct wrapping
parent
ea75666cd8
commit
04c2f80877
|
|
@ -38,7 +38,7 @@ class DSFMap {
|
||||||
DSFMap();
|
DSFMap();
|
||||||
KEY find(const KEY& key) const;
|
KEY find(const KEY& key) const;
|
||||||
void merge(const KEY& x, const KEY& y);
|
void merge(const KEY& x, const KEY& y);
|
||||||
std::map<KEY, Set> sets();
|
std::map<KEY, This::Set> sets();
|
||||||
};
|
};
|
||||||
|
|
||||||
class IndexPairSet {
|
class IndexPairSet {
|
||||||
|
|
|
||||||
|
|
@ -140,7 +140,7 @@ class FitBasis {
|
||||||
static gtsam::GaussianFactorGraph::shared_ptr LinearGraph(
|
static gtsam::GaussianFactorGraph::shared_ptr LinearGraph(
|
||||||
const std::map<double, double>& sequence,
|
const std::map<double, double>& sequence,
|
||||||
const gtsam::noiseModel::Base* model, size_t N);
|
const gtsam::noiseModel::Base* model, size_t N);
|
||||||
Parameters parameters() const;
|
This::Parameters parameters() const;
|
||||||
};
|
};
|
||||||
|
|
||||||
} // namespace gtsam
|
} // namespace gtsam
|
||||||
|
|
|
||||||
|
|
@ -168,7 +168,7 @@ template <POSE>
|
||||||
virtual class PoseTranslationPrior : gtsam::NoiseModelFactor {
|
virtual class PoseTranslationPrior : gtsam::NoiseModelFactor {
|
||||||
PoseTranslationPrior(size_t key, const POSE& pose_z,
|
PoseTranslationPrior(size_t key, const POSE& pose_z,
|
||||||
const gtsam::noiseModel::Base* noiseModel);
|
const gtsam::noiseModel::Base* noiseModel);
|
||||||
POSE measured() const;
|
POSE::Translation measured() const;
|
||||||
|
|
||||||
// enabling serialization functionality
|
// enabling serialization functionality
|
||||||
void serialize() const;
|
void serialize() const;
|
||||||
|
|
@ -185,7 +185,7 @@ template <POSE>
|
||||||
virtual class PoseRotationPrior : gtsam::NoiseModelFactor {
|
virtual class PoseRotationPrior : gtsam::NoiseModelFactor {
|
||||||
PoseRotationPrior(size_t key, const POSE& pose_z,
|
PoseRotationPrior(size_t key, const POSE& pose_z,
|
||||||
const gtsam::noiseModel::Base* noiseModel);
|
const gtsam::noiseModel::Base* noiseModel);
|
||||||
POSE measured() const;
|
POSE::Rotation measured() const;
|
||||||
};
|
};
|
||||||
|
|
||||||
typedef gtsam::PoseRotationPrior<gtsam::Pose2> PoseRotationPrior2D;
|
typedef gtsam::PoseRotationPrior<gtsam::Pose2> PoseRotationPrior2D;
|
||||||
|
|
|
||||||
Loading…
Reference in New Issue