Skip to content

Commit

Permalink
clang tidy fixes
Browse files Browse the repository at this point in the history
  • Loading branch information
henrygerardmoore committed Oct 4, 2024
1 parent 2bb10ff commit 67e661b
Show file tree
Hide file tree
Showing 2 changed files with 17 additions and 21 deletions.
20 changes: 9 additions & 11 deletions fuse_variables/test/test_pinhole_camera.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -52,32 +52,30 @@ using fuse_variables::PinholeCamera;

TEST(PinholeCamera, Type)
{
PinholeCamera variable(0);
PinholeCamera const variable(0);
EXPECT_EQ("fuse_variables::PinholeCamera", variable.type());
}

TEST(PinholeCamera, UUID)
{
// Verify two positions with the same landmark ids produce the same uuids
{
PinholeCamera variable1(0);
PinholeCamera variable2(0);
PinholeCamera const variable1(0);
PinholeCamera const variable2(0);
EXPECT_EQ(variable1.uuid(), variable2.uuid());
}

// Verify two positions with the different landmark ids produce different uuids
{
PinholeCamera variable1(0);
PinholeCamera variable2(1);
PinholeCamera const variable1(0);
PinholeCamera const variable2(1);
EXPECT_NE(variable1.uuid(), variable2.uuid());
}
}

struct CostFunctor
{
CostFunctor()
{
}
CostFunctor() = default;

template <typename T>
bool operator()(const T* const k, T* residual) const
Expand Down Expand Up @@ -273,7 +271,7 @@ struct ProjectionCostFunctor
bool operator()(const T* const k, T* residual) const
{
// Do Projection Manually
std::array<std::array<T, 2>, 8> xp;
std::array<std::array<T, 2>, 8> xp{};
for (uint i = 0; i < 8; i++)
{
xp[i][0] = (T(X[i][0]) * k[0] + T(X[i][2]) * k[2]) / T(X[i][2]); // x = (x*f_x + z * c_x)/z
Expand Down Expand Up @@ -315,7 +313,7 @@ TEST(PinholeCamera, ProjectionOptimization)
problem.AddResidualBlock(cost_function, nullptr, parameter_blocks);

// Run the solver
ceres::Solver::Options options;
ceres::Solver::Options const options;
ceres::Solver::Summary summary;
ceres::Solve(options, &problem, &summary);

Expand Down Expand Up @@ -413,7 +411,7 @@ TEST(PinholeCamera, PerPointProjectionCostFunctor)
}

// Run the solver
ceres::Solver::Options options;
ceres::Solver::Options const options;
ceres::Solver::Summary summary;
ceres::Solve(options, &problem, &summary);

Expand Down
18 changes: 8 additions & 10 deletions fuse_variables/test/test_pinhole_camera_fixed.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -52,32 +52,30 @@ using fuse_variables::PinholeCameraFixed;

TEST(PinholeCameraFixed, Type)
{
PinholeCameraFixed variable(0);
PinholeCameraFixed const variable(0);
EXPECT_EQ("fuse_variables::PinholeCameraFixed", variable.type());
}

TEST(PinholeCameraFixed, UUID)
{
// Verify two positions with the same landmark ids produce the same uuids
{
PinholeCameraFixed variable1(0);
PinholeCameraFixed variable2(0);
PinholeCameraFixed const variable1(0);
PinholeCameraFixed const variable2(0);
EXPECT_EQ(variable1.uuid(), variable2.uuid());
}

// Verify two positions with the different landmark ids produce different uuids
{
PinholeCameraFixed variable1(0);
PinholeCameraFixed variable2(1);
PinholeCameraFixed const variable1(0);
PinholeCameraFixed const variable2(1);
EXPECT_NE(variable1.uuid(), variable2.uuid());
}
}

struct CostFunctor
{
CostFunctor()
{
}
CostFunctor() = default;

template <typename T>
bool operator()(const T* const k, T* residual) const
Expand Down Expand Up @@ -283,7 +281,7 @@ struct ProjectionCostFunctor
bool operator()(const T* const k, T* residual) const
{
// Do Projection Manually
std::array<std::array<T, 2>, 8> xp;
std::array<std::array<T, 2>, 8> xp{};
for (uint i = 0; i < 8; i++)
{
xp[i][0] = (T(X[i][0]) * k[0] + T(X[i][2]) * k[2]) / T(X[i][2]); // x = (x*f_x + z * c_x)/z
Expand Down Expand Up @@ -326,7 +324,7 @@ TEST(PinholeCameraFixed, ProjectionOptimization)
}

// Run the solver
ceres::Solver::Options options;
ceres::Solver::Options const options;
ceres::Solver::Summary summary;
ceres::Solve(options, &problem, &summary);

Expand Down

0 comments on commit 67e661b

Please sign in to comment.