commented out shadowing functions
parent
fe1a9997cf
commit
1312badda4
7
gtsam.h
7
gtsam.h
|
|
@ -252,7 +252,6 @@ class Rot3 {
|
|||
double pitch() const;
|
||||
double yaw() const;
|
||||
// Vector toQuaternion() const; // FIXME: Can't cast to Vector properly
|
||||
Matrix matrix() const;
|
||||
};
|
||||
|
||||
class Pose2 {
|
||||
|
|
@ -306,7 +305,7 @@ class Pose3 {
|
|||
Pose3();
|
||||
Pose3(const gtsam::Pose3& pose);
|
||||
Pose3(const gtsam::Rot3& r, const gtsam::Point3& t);
|
||||
Pose3(const gtsam::Pose2& pose2); // FIXME: shadows Pose3(Pose3 pose)
|
||||
// Pose3(const gtsam::Pose2& pose2); // FIXME: shadows Pose3(Pose3 pose)
|
||||
Pose3(Matrix t);
|
||||
|
||||
// Testable
|
||||
|
|
@ -344,9 +343,9 @@ class Pose3 {
|
|||
double y() const;
|
||||
double z() const;
|
||||
Matrix matrix() const;
|
||||
gtsam::Pose3 transform_to(const gtsam::Pose3& pose) const; // FIXME: shadows other transform_to()
|
||||
// gtsam::Pose3 transform_to(const gtsam::Pose3& pose) const; // FIXME: shadows other transform_to()
|
||||
double range(const gtsam::Point3& point);
|
||||
// double range(const gtsam::Pose3& pose);
|
||||
// double range(const gtsam::Pose3& pose); // FIXME: shadows other range
|
||||
};
|
||||
|
||||
class Cal3_S2 {
|
||||
|
|
|
|||
Loading…
Reference in New Issue