Skip to content

Commit

Permalink
Merge pull request #2000 from leocencetti/fix-test-errors
Browse files Browse the repository at this point in the history
Fix  test errors in 3x3 covariance test cases
  • Loading branch information
vooon authored Oct 10, 2024
2 parents f5e4f1f + 0a9a361 commit 166e832
Showing 1 changed file with 4 additions and 4 deletions.
8 changes: 4 additions & 4 deletions mavros/test/test_frame_conversions.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -170,7 +170,7 @@ TEST(FRAME_TF, transform_frame__covariance3x3)
Eigen::AngleAxisd(0.0, Eigen::Vector3d::UnitZ()) *
Eigen::AngleAxisd(0.0, Eigen::Vector3d::UnitY()) *
Eigen::AngleAxisd(M_PI, Eigen::Vector3d::UnitX())
)
);

/* Calculated as:
*
Expand All @@ -188,7 +188,7 @@ TEST(FRAME_TF, transform_frame__covariance3x3)
-7.0, 8.0, 9.0
}};

auto out = ftf::transform_frame(input, q);
auto out = ftf::detail::transform_frame(input, q);

for (size_t idx = 0; idx < expected.size(); idx++) {
SCOPED_TRACE(idx);
Expand All @@ -212,7 +212,7 @@ TEST(FRAME_TF, transform_frame__covariance6x6)
Eigen::AngleAxisd(0.0, Eigen::Vector3d::UnitZ()) *
Eigen::AngleAxisd(0.0, Eigen::Vector3d::UnitY()) *
Eigen::AngleAxisd(M_PI, Eigen::Vector3d::UnitX())
)
);

/* Calculated as:
*
Expand All @@ -236,7 +236,7 @@ TEST(FRAME_TF, transform_frame__covariance6x6)
-31.0, 32.0, 33.0, -34.0, 35.0, 36.0
}};

auto out = ftf::transform_frame(input, q);
auto out = ftf::detail::transform_frame(input, q);

for (size_t idx = 0; idx < expected.size(); idx++) {
SCOPED_TRACE(idx);
Expand Down

0 comments on commit 166e832

Please sign in to comment.