Skip to content

Commit

Permalink
Merge pull request #1238 from borglab/fix/1182
Browse files Browse the repository at this point in the history
Capitalize Identity trait
  • Loading branch information
varunagrawal authored Aug 21, 2022
2 parents d3544d4 + c31298d commit 0f53b3f
Show file tree
Hide file tree
Showing 44 changed files with 135 additions and 135 deletions.
8 changes: 4 additions & 4 deletions gtsam/base/Group.h
Original file line number Diff line number Diff line change
Expand Up @@ -95,7 +95,7 @@ template<class Class>
struct MultiplicativeGroupTraits {
typedef group_tag structure_category;
typedef multiplicative_group_tag group_flavor;
static Class Identity() { return Class::identity(); }
static Class Identity() { return Class::Identity(); }
static Class Compose(const Class &g, const Class & h) { return g * h;}
static Class Between(const Class &g, const Class & h) { return g.inverse() * h;}
static Class Inverse(const Class &g) { return g.inverse();}
Expand All @@ -111,7 +111,7 @@ template<class Class>
struct AdditiveGroupTraits {
typedef group_tag structure_category;
typedef additive_group_tag group_flavor;
static Class Identity() { return Class::identity(); }
static Class Identity() { return Class::Identity(); }
static Class Compose(const Class &g, const Class & h) { return g + h;}
static Class Between(const Class &g, const Class & h) { return h - g;}
static Class Inverse(const Class &g) { return -g;}
Expand Down Expand Up @@ -147,7 +147,7 @@ class DirectProduct: public std::pair<G, H> {
DirectProduct(const G& g, const H& h):std::pair<G,H>(g,h) {}

// identity
static DirectProduct identity() { return DirectProduct(); }
static DirectProduct Identity() { return DirectProduct(); }

DirectProduct operator*(const DirectProduct& other) const {
return DirectProduct(traits<G>::Compose(this->first, other.first),
Expand Down Expand Up @@ -181,7 +181,7 @@ class DirectSum: public std::pair<G, H> {
DirectSum(const G& g, const H& h):std::pair<G,H>(g,h) {}

// identity
static DirectSum identity() { return DirectSum(); }
static DirectSum Identity() { return DirectSum(); }

DirectSum operator+(const DirectSum& other) const {
return DirectSum(g()+other.g(), h()+other.h());
Expand Down
2 changes: 1 addition & 1 deletion gtsam/base/Lie.h
Original file line number Diff line number Diff line change
Expand Up @@ -177,7 +177,7 @@ struct LieGroupTraits: GetDimensionImpl<Class, Class::dimension> {
/// @name Group
/// @{
typedef multiplicative_group_tag group_flavor;
static Class Identity() { return Class::identity();}
static Class Identity() { return Class::Identity();}
/// @}

/// @name Manifold
Expand Down
2 changes: 1 addition & 1 deletion gtsam/base/ProductLieGroup.h
Original file line number Diff line number Diff line change
Expand Up @@ -48,7 +48,7 @@ class ProductLieGroup: public std::pair<G, H> {
/// @name Group
/// @{
typedef multiplicative_group_tag group_flavor;
static ProductLieGroup identity() {return ProductLieGroup();}
static ProductLieGroup Identity() {return ProductLieGroup();}

ProductLieGroup operator*(const ProductLieGroup& other) const {
return ProductLieGroup(traits<G>::Compose(this->first,other.first),
Expand Down
4 changes: 2 additions & 2 deletions gtsam/base/VectorSpace.h
Original file line number Diff line number Diff line change
Expand Up @@ -169,7 +169,7 @@ struct HasVectorSpacePrereqs {
Vector v;

BOOST_CONCEPT_USAGE(HasVectorSpacePrereqs) {
p = Class::identity(); // identity
p = Class::Identity(); // identity
q = p + p; // addition
q = p - p; // subtraction
v = p.vector(); // conversion to vector
Expand All @@ -192,7 +192,7 @@ struct VectorSpaceTraits: VectorSpaceImpl<Class, Class::dimension> {
/// @name Group
/// @{
typedef additive_group_tag group_flavor;
static Class Identity() { return Class::identity();}
static Class Identity() { return Class::Identity();}
/// @}

/// @name Manifold
Expand Down
2 changes: 1 addition & 1 deletion gtsam/base/tests/testGroup.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,7 @@ class Symmetric: private Eigen::PermutationMatrix<N> {
Eigen::PermutationMatrix<N>(P) {
}
public:
static Symmetric identity() { return Symmetric(); }
static Symmetric Identity() { return Symmetric(); }
Symmetric() {
Eigen::PermutationMatrix<N>::setIdentity();
}
Expand Down
4 changes: 2 additions & 2 deletions gtsam/basis/ParameterMatrix.h
Original file line number Diff line number Diff line change
Expand Up @@ -189,9 +189,9 @@ class ParameterMatrix {
* NOTE: The size at compile time is unknown so this identity is zero
* length and thus not valid.
*/
inline static ParameterMatrix identity() {
inline static ParameterMatrix Identity() {
// throw std::runtime_error(
// "ParameterMatrix::identity(): Don't use this function");
// "ParameterMatrix::Identity(): Don't use this function");
return ParameterMatrix(0);
}

Expand Down
2 changes: 1 addition & 1 deletion gtsam/basis/tests/testParameterMatrix.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -133,7 +133,7 @@ TEST(ParameterMatrix, VectorSpace) {
// vector
EXPECT(assert_equal(Vector::Ones(M * N), params.vector()));
// identity
EXPECT(assert_equal(ParameterMatrix<M>::identity(),
EXPECT(assert_equal(ParameterMatrix<M>::Identity(),
ParameterMatrix<M>(Matrix::Zero(M, 0))));
}

Expand Down
2 changes: 1 addition & 1 deletion gtsam/geometry/Cyclic.h
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,7 @@ class Cyclic {
/// Default constructor yields identity
Cyclic():i_(0) {
}
static Cyclic identity() { return Cyclic();}
static Cyclic Identity() { return Cyclic();}

/// Cast to size_t
operator size_t() const {
Expand Down
2 changes: 1 addition & 1 deletion gtsam/geometry/PinholeCamera.h
Original file line number Diff line number Diff line change
Expand Up @@ -213,7 +213,7 @@ class PinholeCamera: public PinholeBaseK<Calibration> {
}

/// for Canonical
static PinholeCamera identity() {
static PinholeCamera Identity() {
return PinholeCamera(); // assumes that the default constructor is valid
}

Expand Down
2 changes: 1 addition & 1 deletion gtsam/geometry/PinholePose.h
Original file line number Diff line number Diff line change
Expand Up @@ -412,7 +412,7 @@ class PinholePose: public PinholeBaseK<CALIBRATION> {
}

/// for Canonical
static PinholePose identity() {
static PinholePose Identity() {
return PinholePose(); // assumes that the default constructor is valid
}

Expand Down
2 changes: 1 addition & 1 deletion gtsam/geometry/Pose2.h
Original file line number Diff line number Diff line change
Expand Up @@ -119,7 +119,7 @@ class Pose2: public LieGroup<Pose2, 3> {
/// @{

/// identity for group operation
inline static Pose2 identity() { return Pose2(); }
inline static Pose2 Identity() { return Pose2(); }

/// inverse
GTSAM_EXPORT Pose2 inverse() const;
Expand Down
2 changes: 1 addition & 1 deletion gtsam/geometry/Pose3.h
Original file line number Diff line number Diff line change
Expand Up @@ -103,7 +103,7 @@ class GTSAM_EXPORT Pose3: public LieGroup<Pose3, 6> {
/// @{

/// identity for group operation
static Pose3 identity() {
static Pose3 Identity() {
return Pose3();
}

Expand Down
4 changes: 2 additions & 2 deletions gtsam/geometry/Rot2.h
Original file line number Diff line number Diff line change
Expand Up @@ -107,8 +107,8 @@ namespace gtsam {
/// @name Group
/// @{

/** identity */
inline static Rot2 identity() { return Rot2(); }
/** Identity */
inline static Rot2 Identity() { return Rot2(); }

/** The inverse rotation - negative angle */
Rot2 inverse() const { return Rot2(c_, -s_);}
Expand Down
2 changes: 1 addition & 1 deletion gtsam/geometry/Rot3.h
Original file line number Diff line number Diff line change
Expand Up @@ -297,7 +297,7 @@ class GTSAM_EXPORT Rot3 : public LieGroup<Rot3, 3> {
/// @{

/// identity rotation for group operation
inline static Rot3 identity() {
inline static Rot3 Identity() {
return Rot3();
}

Expand Down
4 changes: 2 additions & 2 deletions gtsam/geometry/SOn.h
Original file line number Diff line number Diff line change
Expand Up @@ -178,13 +178,13 @@ class SO : public LieGroup<SO<N>, internal::DimensionSO(N)> {

/// SO<N> identity for N >= 2
template <int N_ = N, typename = IsFixed<N_>>
static SO identity() {
static SO Identity() {
return SO();
}

/// SO<N> identity for N == Eigen::Dynamic
template <int N_ = N, typename = IsDynamic<N_>>
static SO identity(size_t n = 0) {
static SO Identity(size_t n = 0) {
return SO(n);
}

Expand Down
2 changes: 1 addition & 1 deletion gtsam/geometry/Similarity2.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -134,7 +134,7 @@ void Similarity2::print(const std::string& s) const {
<< std::endl;
}

Similarity2 Similarity2::identity() { return Similarity2(); }
Similarity2 Similarity2::Identity() { return Similarity2(); }

Similarity2 Similarity2::operator*(const Similarity2& S) const {
return Similarity2(R_ * S.R_, ((1.0 / S.s_) * t_) + R_ * S.t_, s_ * S.s_);
Expand Down
2 changes: 1 addition & 1 deletion gtsam/geometry/Similarity2.h
Original file line number Diff line number Diff line change
Expand Up @@ -83,7 +83,7 @@ class GTSAM_EXPORT Similarity2 : public LieGroup<Similarity2, 4> {
/// @{

/// Return an identity transform
static Similarity2 identity();
static Similarity2 Identity();

/// Composition
Similarity2 operator*(const Similarity2& S) const;
Expand Down
2 changes: 1 addition & 1 deletion gtsam/geometry/Similarity3.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -122,7 +122,7 @@ void Similarity3::print(const std::string& s) const {
std::cout << "t: " << translation().transpose() << " s: " << scale() << std::endl;
}

Similarity3 Similarity3::identity() {
Similarity3 Similarity3::Identity() {
return Similarity3();
}
Similarity3 Similarity3::operator*(const Similarity3& S) const {
Expand Down
2 changes: 1 addition & 1 deletion gtsam/geometry/Similarity3.h
Original file line number Diff line number Diff line change
Expand Up @@ -84,7 +84,7 @@ class GTSAM_EXPORT Similarity3 : public LieGroup<Similarity3, 7> {
/// @{

/// Return an identity transform
static Similarity3 identity();
static Similarity3 Identity();

/// Composition
Similarity3 operator*(const Similarity3& S) const;
Expand Down
6 changes: 3 additions & 3 deletions gtsam/geometry/SphericalCamera.h
Original file line number Diff line number Diff line change
Expand Up @@ -88,7 +88,7 @@ class GTSAM_EXPORT SphericalCamera {

/// Default constructor
SphericalCamera()
: pose_(Pose3::identity()), emptyCal_(boost::make_shared<EmptyCal>()) {}
: pose_(Pose3()), emptyCal_(boost::make_shared<EmptyCal>()) {}

/// Constructor with pose
explicit SphericalCamera(const Pose3& pose)
Expand Down Expand Up @@ -198,9 +198,9 @@ class GTSAM_EXPORT SphericalCamera {
}

/// for Canonical
static SphericalCamera identity() {
static SphericalCamera Identity() {
return SphericalCamera(
Pose3::identity()); // assumes that the default constructor is valid
Pose3::Identity()); // assumes that the default constructor is valid
}

/// for Linear Triangulation
Expand Down
2 changes: 1 addition & 1 deletion gtsam/geometry/StereoPoint2.h
Original file line number Diff line number Diff line change
Expand Up @@ -71,7 +71,7 @@ class GTSAM_EXPORT StereoPoint2 {
/// @{

/// identity
inline static StereoPoint2 identity() {
inline static StereoPoint2 Identity() {
return StereoPoint2();
}

Expand Down
20 changes: 10 additions & 10 deletions gtsam/geometry/geometry.i
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,7 @@ class Point2 {
bool equals(const gtsam::Point2& point, double tol) const;

// Group
static gtsam::Point2 identity();
static gtsam::Point2 Identity();

// Standard Interface
double x() const;
Expand Down Expand Up @@ -73,7 +73,7 @@ class StereoPoint2 {
bool equals(const gtsam::StereoPoint2& point, double tol) const;

// Group
static gtsam::StereoPoint2 identity();
static gtsam::StereoPoint2 Identity();
gtsam::StereoPoint2 inverse() const;
gtsam::StereoPoint2 compose(const gtsam::StereoPoint2& p2) const;
gtsam::StereoPoint2 between(const gtsam::StereoPoint2& p2) const;
Expand Down Expand Up @@ -115,7 +115,7 @@ class Point3 {
bool equals(const gtsam::Point3& p, double tol) const;

// Group
static gtsam::Point3 identity();
static gtsam::Point3 Identity();

// Standard Interface
Vector vector() const;
Expand Down Expand Up @@ -149,7 +149,7 @@ class Rot2 {
bool equals(const gtsam::Rot2& rot, double tol) const;

// Group
static gtsam::Rot2 identity();
static gtsam::Rot2 Identity();
gtsam::Rot2 inverse();
gtsam::Rot2 compose(const gtsam::Rot2& p2) const;
gtsam::Rot2 between(const gtsam::Rot2& p2) const;
Expand Down Expand Up @@ -198,7 +198,7 @@ class SO3 {
bool equals(const gtsam::SO3& other, double tol) const;

// Group
static gtsam::SO3 identity();
static gtsam::SO3 Identity();
gtsam::SO3 inverse() const;
gtsam::SO3 between(const gtsam::SO3& R) const;
gtsam::SO3 compose(const gtsam::SO3& R) const;
Expand Down Expand Up @@ -228,7 +228,7 @@ class SO4 {
bool equals(const gtsam::SO4& other, double tol) const;

// Group
static gtsam::SO4 identity();
static gtsam::SO4 Identity();
gtsam::SO4 inverse() const;
gtsam::SO4 between(const gtsam::SO4& Q) const;
gtsam::SO4 compose(const gtsam::SO4& Q) const;
Expand Down Expand Up @@ -258,7 +258,7 @@ class SOn {
bool equals(const gtsam::SOn& other, double tol) const;

// Group
static gtsam::SOn identity();
static gtsam::SOn Identity();
gtsam::SOn inverse() const;
gtsam::SOn between(const gtsam::SOn& Q) const;
gtsam::SOn compose(const gtsam::SOn& Q) const;
Expand Down Expand Up @@ -322,7 +322,7 @@ class Rot3 {
bool equals(const gtsam::Rot3& rot, double tol) const;

// Group
static gtsam::Rot3 identity();
static gtsam::Rot3 Identity();
gtsam::Rot3 inverse() const;
gtsam::Rot3 compose(const gtsam::Rot3& p2) const;
gtsam::Rot3 between(const gtsam::Rot3& p2) const;
Expand Down Expand Up @@ -380,7 +380,7 @@ class Pose2 {
bool equals(const gtsam::Pose2& pose, double tol) const;

// Group
static gtsam::Pose2 identity();
static gtsam::Pose2 Identity();
gtsam::Pose2 inverse() const;
gtsam::Pose2 compose(const gtsam::Pose2& p2) const;
gtsam::Pose2 between(const gtsam::Pose2& p2) const;
Expand Down Expand Up @@ -444,7 +444,7 @@ class Pose3 {
bool equals(const gtsam::Pose3& pose, double tol) const;

// Group
static gtsam::Pose3 identity();
static gtsam::Pose3 Identity();
gtsam::Pose3 inverse() const;
gtsam::Pose3 inverse(Eigen::Ref<Eigen::MatrixXd> H) const;
gtsam::Pose3 compose(const gtsam::Pose3& pose) const;
Expand Down
2 changes: 1 addition & 1 deletion gtsam/geometry/tests/testPose2.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -902,7 +902,7 @@ TEST(Pose2 , TransformCovariance3) {

/* ************************************************************************* */
TEST(Pose2, Print) {
Pose2 pose(Rot2::identity(), Point2(1, 2));
Pose2 pose(Rot2::Identity(), Point2(1, 2));

// Generate the expected output
string s = "Planar Pose";
Expand Down
12 changes: 6 additions & 6 deletions gtsam/geometry/tests/testPose3.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1133,7 +1133,7 @@ Pose3 testing_interpolate(const Pose3& t1, const Pose3& t2, double gamma) { retu

TEST(Pose3, interpolateJacobians) {
{
Pose3 X = Pose3::identity();
Pose3 X = Pose3::Identity();
Pose3 Y(Rot3::Rz(M_PI_2), Point3(1, 0, 0));
double t = 0.5;
Pose3 expectedPoseInterp(Rot3::Rz(M_PI_4), Point3(0.5, -0.207107, 0)); // note: different from test above: this is full Pose3 interpolation
Expand All @@ -1147,10 +1147,10 @@ TEST(Pose3, interpolateJacobians) {
EXPECT(assert_equal(expectedJacobianY,actualJacobianY,1e-6));
}
{
Pose3 X = Pose3::identity();
Pose3 Y(Rot3::identity(), Point3(1, 0, 0));
Pose3 X = Pose3::Identity();
Pose3 Y(Rot3::Identity(), Point3(1, 0, 0));
double t = 0.3;
Pose3 expectedPoseInterp(Rot3::identity(), Point3(0.3, 0, 0));
Pose3 expectedPoseInterp(Rot3::Identity(), Point3(0.3, 0, 0));
Matrix actualJacobianX, actualJacobianY;
EXPECT(assert_equal(expectedPoseInterp, interpolate(X, Y, t, actualJacobianX, actualJacobianY), 1e-5));

Expand All @@ -1161,7 +1161,7 @@ TEST(Pose3, interpolateJacobians) {
EXPECT(assert_equal(expectedJacobianY,actualJacobianY,1e-6));
}
{
Pose3 X = Pose3::identity();
Pose3 X = Pose3::Identity();
Pose3 Y(Rot3::Rz(M_PI_2), Point3(0, 0, 0));
double t = 0.5;
Pose3 expectedPoseInterp(Rot3::Rz(M_PI_4), Point3(0, 0, 0));
Expand Down Expand Up @@ -1204,7 +1204,7 @@ TEST(Pose3, Create) {

/* ************************************************************************* */
TEST(Pose3, Print) {
Pose3 pose(Rot3::identity(), Point3(1, 2, 3));
Pose3 pose(Rot3::Identity(), Point3(1, 2, 3));

// Generate the expected output
std::string expected = "R: [\n\t1, 0, 0;\n\t0, 1, 0;\n\t0, 0, 1\n]\nt: 1 2 3\n";
Expand Down
Loading

0 comments on commit 0f53b3f

Please sign in to comment.