Renamed landmarkSymbol_ to landmarkKey_
parent
411d3a2273
commit
3c21c31353
|
|
@ -15,7 +15,7 @@ namespace gtsam {
|
||||||
//***************************************************************************
|
//***************************************************************************
|
||||||
|
|
||||||
void OrientedPlane3DirectionPrior::print(const string& s) const {
|
void OrientedPlane3DirectionPrior::print(const string& s) const {
|
||||||
cout << "Prior Factor on " << landmarkSymbol_ << "\n";
|
cout << "Prior Factor on " << landmarkKey_ << "\n";
|
||||||
measured_p_.print("Measured Plane");
|
measured_p_.print("Measured Plane");
|
||||||
this->noiseModel_->print(" noise model: ");
|
this->noiseModel_->print(" noise model: ");
|
||||||
}
|
}
|
||||||
|
|
|
||||||
|
|
@ -65,7 +65,7 @@ namespace gtsam {
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
OrientedPlane3 measured_p_; /// measured plane parameters
|
OrientedPlane3 measured_p_; /// measured plane parameters
|
||||||
Key landmarkSymbol_;
|
Key landmarkKey_;
|
||||||
|
|
||||||
typedef NoiseModelFactor1<OrientedPlane3 > Base;
|
typedef NoiseModelFactor1<OrientedPlane3 > Base;
|
||||||
|
|
||||||
|
|
@ -80,7 +80,7 @@ namespace gtsam {
|
||||||
OrientedPlane3DirectionPrior (Key key, const Vector&z,
|
OrientedPlane3DirectionPrior (Key key, const Vector&z,
|
||||||
const SharedGaussian& noiseModel)
|
const SharedGaussian& noiseModel)
|
||||||
: Base (noiseModel, key),
|
: Base (noiseModel, key),
|
||||||
landmarkSymbol_ (key)
|
landmarkKey_ (key)
|
||||||
{
|
{
|
||||||
measured_p_ = OrientedPlane3 (Sphere2 (z (0), z (1), z (2)), z (3));
|
measured_p_ = OrientedPlane3 (Sphere2 (z (0), z (1), z (2)), z (3));
|
||||||
}
|
}
|
||||||
|
|
|
||||||
Loading…
Reference in New Issue