-
Notifications
You must be signed in to change notification settings - Fork 0
refactor: restructure vortex_utils and add more C++ utils #10
New issue
Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.
By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.
Already on GitHub? Sign in to your account
Changes from 22 commits
54fff4a
8c63f9e
ab2256d
23c6082
c2a4b0a
b9dfcc4
ff736bb
49f15d3
93a9386
5fd034c
b7a3074
15ac439
f6a5d99
ca2932f
0e4a22f
701f199
4ff6c46
d7325a7
3d37d90
1055f06
73c2833
8b9aa36
4ed8328
File filter
Filter by extension
Conversations
Jump to
Diff view
Diff view
There are no files selected for viewing
| Original file line number | Diff line number | Diff line change |
|---|---|---|
| @@ -0,0 +1,23 @@ | ||
| cmake_minimum_required(VERSION 3.8) | ||
|
|
||
| find_package(GTest REQUIRED) | ||
| include(GoogleTest) | ||
|
|
||
| set(TEST_BINARY_NAME ${PROJECT_NAME}_test) | ||
| add_executable( | ||
| ${TEST_BINARY_NAME} | ||
| test_math.cpp | ||
| test_types.cpp | ||
| ) | ||
|
|
||
| target_link_libraries( | ||
| ${TEST_BINARY_NAME} | ||
| PRIVATE | ||
| ${PROJECT_NAME} | ||
| GTest::GTest | ||
| GTest::gtest_main | ||
| ) | ||
|
|
||
| ament_target_dependencies(${TEST_BINARY_NAME} PUBLIC Eigen3) | ||
|
|
||
| gtest_discover_tests(${TEST_BINARY_NAME}) |
| Original file line number | Diff line number | Diff line change |
|---|---|---|
| @@ -0,0 +1,6 @@ | ||
| #include <gtest/gtest.h> | ||
|
|
||
| int main(int argc, char** argv) { | ||
| ::testing::InitGoogleTest(&argc, argv); | ||
| return RUN_ALL_TESTS(); | ||
| } |
| Original file line number | Diff line number | Diff line change | ||||
|---|---|---|---|---|---|---|
| @@ -0,0 +1,171 @@ | ||||||
| #include <gtest/gtest.h> | ||||||
| #include "vortex/utils/math.hpp" | ||||||
|
|
||||||
| namespace vortex::utils::math { | ||||||
|
|
||||||
| // Test that the value does not change when already in the interval [-pi, pi] | ||||||
| TEST(ssa, test_ssa_0) { | ||||||
| EXPECT_EQ(0, ssa(0)); | ||||||
| } | ||||||
|
|
||||||
| // Test that 2 pi correctly maps to 0 | ||||||
| TEST(ssa, test_ssa_2pi) { | ||||||
| EXPECT_EQ(0, ssa(2 * M_PI)); | ||||||
| } | ||||||
|
|
||||||
| // Test that values over pi gets mapped to the negative interval | ||||||
| TEST(ssa, test_ssa_3_5) { | ||||||
| EXPECT_NEAR(-2.78, ssa(3.5), 0.01); | ||||||
| } | ||||||
|
|
||||||
| // Test that values under -pi gets mapped to the positive interval | ||||||
| TEST(ssa, test_ssa_minus_3_5) { | ||||||
| EXPECT_NEAR(2.78, ssa(-3.5), 0.01); | ||||||
| } | ||||||
|
|
||||||
| // Test that the skew-symmetric matrix is correctly calculated | ||||||
| TEST(get_skew_symmetric_matrix, test_skew_symmetric) { | ||||||
| Eigen::Vector3d vector(1, 2, 3); | ||||||
| Eigen::Matrix3d expected; | ||||||
| expected << 0, -3, 2, 3, 0, -1, -2, 1, 0; | ||||||
|
|
||||||
| Eigen::Matrix3d result = get_skew_symmetric_matrix(vector); | ||||||
| EXPECT_EQ(expected, result); | ||||||
| } | ||||||
|
|
||||||
| // Test that rotation matrix is correctly constructed | ||||||
| TEST(get_rotation_matrix, test_rotation_matrix) { | ||||||
| double roll{1.0}; | ||||||
| double pitch{2.0}; | ||||||
| double yaw{3.0}; | ||||||
| Eigen::Matrix3d expected; | ||||||
| expected << 0.41198225, -0.83373765, -0.36763046, -0.05872664, -0.42691762, | ||||||
| 0.90238159, -0.90929743, -0.35017549, -0.2248451; | ||||||
| Eigen::Matrix3d result = get_rotation_matrix(roll, pitch, yaw); | ||||||
| EXPECT_NEAR(0.0, matrix_norm_diff(expected, result), 0.01); | ||||||
| } | ||||||
|
|
||||||
| TEST(get_transformation_matrix_attitude, test_transformation_matrix_zeros) { | ||||||
| Eigen::Matrix3d transformation_matrix{ | ||||||
| get_transformation_matrix_attitude(0.0, 0.0)}; | ||||||
| Eigen::Matrix3d expected{Eigen::Matrix3d::Identity()}; | ||||||
| EXPECT_NEAR(0.0, matrix_norm_diff(expected, transformation_matrix), 0.01); | ||||||
| } | ||||||
|
|
||||||
| // Test that the identity quaternion correctly maps to 0, 0, 0 | ||||||
| TEST(quat_to_euler, test_quat_to_euler_1) { | ||||||
| Eigen::Quaterniond q(1.0, 0.0, 0.0, 0.0); | ||||||
| Eigen::Vector3d expected(0.0, 0.0, 0.0); | ||||||
| Eigen::Vector3d result = quat_to_euler(q); | ||||||
| for (int i = 0; i < 3; ++i) { | ||||||
| EXPECT_NEAR(expected[i], result[i], 0.01); | ||||||
| } | ||||||
| } | ||||||
|
|
||||||
| // Test that only changing w and x in the quat only affects roll | ||||||
| TEST(quat_to_euler, test_quat_to_euler_2) { | ||||||
| Eigen::Quaterniond q2(0.707, 0.707, 0.0, 0.0); | ||||||
| Eigen::Vector3d expected2(1.57, 0.0, 0.0); | ||||||
| Eigen::Vector3d result2 = quat_to_euler(q2); | ||||||
| for (int i = 0; i < 3; ++i) { | ||||||
| EXPECT_NEAR(expected2[i], result2[i], 0.01); | ||||||
| } | ||||||
| } | ||||||
|
|
||||||
| // Test that only changing w and z in the quat only affects yaw | ||||||
| TEST(quat_to_euler, test_quat_to_euler_3) { | ||||||
| Eigen::Quaterniond q4(0.707, 0.0, 0.0, 0.707); | ||||||
| Eigen::Vector3d expected4(0.0, 0.0, 1.57); | ||||||
| Eigen::Vector3d result4 = quat_to_euler(q4); | ||||||
| for (int i = 0; i < 3; ++i) { | ||||||
| EXPECT_NEAR(expected4[i], result4[i], 0.01); | ||||||
| } | ||||||
| } | ||||||
|
|
||||||
| // Test that a quaternion is correctly converted to euler angles | ||||||
| TEST(quat_to_euler, test_quat_to_euler_4) { | ||||||
| Eigen::Quaterniond q5(0.770, 0.4207, -0.4207, -0.229); | ||||||
| Eigen::Vector3d expected5(1.237, -0.4729, -0.9179); | ||||||
| Eigen::Vector3d result5 = quat_to_euler(q5); | ||||||
| for (int i = 0; i < 3; ++i) { | ||||||
| EXPECT_NEAR(expected5[i], result5[i], 0.01); | ||||||
| } | ||||||
| } | ||||||
|
|
||||||
| // Test that a quaternion with flipped signs is correctly convverted to euler | ||||||
| // angles | ||||||
| TEST(quat_to_euler, test_quat_to_euler_5) { | ||||||
| Eigen::Quaterniond q5(0.770, 0.4207, 0.4207, 0.229); | ||||||
| Eigen::Vector3d expected5(1.237, 0.4729, 0.9179); | ||||||
| Eigen::Vector3d result5 = quat_to_euler(q5); | ||||||
| for (int i = 0; i < 3; ++i) { | ||||||
| EXPECT_NEAR(expected5[i], result5[i], 0.01); | ||||||
| } | ||||||
| } | ||||||
|
|
||||||
| // Test that zero euler angles construct the correct quaternion | ||||||
| TEST(euler_to_quat, test_euler_to_quat_1) { | ||||||
| double roll{}; | ||||||
| double pitch{}; | ||||||
| double yaw{}; | ||||||
| Eigen::Quaterniond q{euler_to_quat(roll, pitch, yaw)}; | ||||||
| Eigen::Vector4d result{q.x(), q.y(), q.z(), q.w()}; | ||||||
| Eigen::Vector4d expected{0.0, 0.0, 0.0, 1.0}; | ||||||
| for (int i = 0; i < 3; ++i) { | ||||||
|
||||||
| for (int i = 0; i < 3; ++i) { | |
| for (int i = 0; i < 4; ++i) { |
Outdated
Copilot
AI
Oct 13, 2025
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Loop should iterate through all 4 quaternion components (0 to 3), not just the first 3. The quaternion has x, y, z, w components.
Outdated
Copilot
AI
Oct 13, 2025
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Loop should iterate through all 4 quaternion components (0 to 3), not just the first 3. The quaternion has x, y, z, w components.
Outdated
Copilot
AI
Oct 13, 2025
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Loop should iterate through all 4 quaternion components (0 to 3), not just the first 3. The quaternion has x, y, z, w components.
Outdated
Copilot
AI
Oct 13, 2025
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Loop should iterate through all 4 quaternion components (0 to 3), not just the first 3. The quaternion has x, y, z, w components.
| Original file line number | Diff line number | Diff line change |
|---|---|---|
| @@ -0,0 +1,93 @@ | ||
| #include <gtest/gtest.h> | ||
|
|
||
| #include "vortex/utils/math.hpp" | ||
| #include "vortex/utils/types.hpp" | ||
|
|
||
| class TypesTests : public ::testing::Test { | ||
| public: | ||
| TypesTests() = default; | ||
| void SetUp() override {} | ||
| }; | ||
|
|
||
| TEST_F(TypesTests, test_eta) { | ||
| vortex::utils::types::Eta eta; | ||
| // Test correct zero initialization | ||
| EXPECT_EQ(eta.x, 0.0); | ||
| EXPECT_EQ(eta.y, 0.0); | ||
| EXPECT_EQ(eta.z, 0.0); | ||
| EXPECT_EQ(eta.roll, 0.0); | ||
| EXPECT_EQ(eta.pitch, 0.0); | ||
| EXPECT_EQ(eta.yaw, 0.0); | ||
|
|
||
| // Test rotation and transformation matrix | ||
| eta.roll = 1.0; | ||
| eta.pitch = 0.5; | ||
| eta.yaw = 1.7; | ||
| Eigen::Matrix3d expected_rm{ | ||
| vortex::utils::math::get_rotation_matrix(1.0, 0.5, 1.7)}; | ||
| Eigen::Matrix3d result_rm{eta.as_rotation_matrix()}; | ||
| double diff_rm{ | ||
| vortex::utils::math::matrix_norm_diff(expected_rm, result_rm)}; | ||
| EXPECT_NEAR(diff_rm, 0.0, 1e-12); | ||
|
|
||
| Eigen::Matrix3d expected_tm{ | ||
| vortex::utils::math::get_transformation_matrix_attitude(1.0, 0.5)}; | ||
| Eigen::Matrix3d result_tm{eta.as_transformation_matrix()}; | ||
| double diff_tm{ | ||
| vortex::utils::math::matrix_norm_diff(expected_tm, result_tm)}; | ||
| EXPECT_NEAR(diff_tm, 0.0, 1e-12); | ||
|
|
||
| // Test to_vector | ||
| eta.x = 5.0; | ||
| eta.y = -4.0; | ||
| eta.z = 2.1; | ||
| Eigen::Vector6d result_v{eta.to_vector()}; | ||
| Eigen::Vector6d expected_v{5.0, -4.0, 2.1, 1.0, 0.5, 1.7}; | ||
| for (int i = 0; i < 6; ++i) { | ||
| EXPECT_NEAR(expected_v[i], result_v[i], 1e-12); | ||
| } | ||
|
|
||
| // Test operator- | ||
| vortex::utils::types::Eta other{1.0, 2.0, 3.0, 0.1, 0.2, 0.3}; | ||
| vortex::utils::types::Eta diff{eta - other}; | ||
| EXPECT_NEAR(diff.x, 4.0, 1e-12); | ||
| EXPECT_NEAR(diff.y, -6.0, 1e-12); | ||
| EXPECT_NEAR(diff.z, -0.9, 1e-12); | ||
| EXPECT_NEAR(diff.roll, 0.9, 1e-12); | ||
| EXPECT_NEAR(diff.pitch, 0.3, 1e-12); | ||
| EXPECT_NEAR(diff.yaw, 1.4, 1e-12); | ||
| } | ||
|
|
||
| TEST_F(TypesTests, test_nu) { | ||
| vortex::utils::types::Nu nu; | ||
| // Test correct zero initialization | ||
| EXPECT_EQ(nu.u, 0.0); | ||
| EXPECT_EQ(nu.v, 0.0); | ||
| EXPECT_EQ(nu.w, 0.0); | ||
| EXPECT_EQ(nu.p, 0.0); | ||
| EXPECT_EQ(nu.q, 0.0); | ||
| EXPECT_EQ(nu.r, 0.0); | ||
|
|
||
| // Test to_vector | ||
| nu.u = 5.0; | ||
| nu.v = -4.0; | ||
| nu.w = 2.1; | ||
| nu.p = 1.0; | ||
| nu.q = 0.5; | ||
| nu.r = 1.7; | ||
| Eigen::Vector6d result_v{nu.to_vector()}; | ||
| Eigen::Vector6d expected_v{5.0, -4.0, 2.1, 1.0, 0.5, 1.7}; | ||
| for (int i = 0; i < 6; ++i) { | ||
| EXPECT_NEAR(expected_v[i], result_v[i], 1e-12); | ||
| } | ||
|
|
||
| // Test operator- | ||
| vortex::utils::types::Nu other{1.0, 2.0, 3.0, 0.1, 0.2, 0.3}; | ||
| vortex::utils::types::Nu diff{nu - other}; | ||
| EXPECT_NEAR(diff.u, 4.0, 1e-12); | ||
| EXPECT_NEAR(diff.v, -6.0, 1e-12); | ||
| EXPECT_NEAR(diff.w, -0.9, 1e-12); | ||
| EXPECT_NEAR(diff.p, 0.9, 1e-12); | ||
| EXPECT_NEAR(diff.q, 0.3, 1e-12); | ||
| EXPECT_NEAR(diff.r, 1.4, 1e-12); | ||
| } |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Corrected spelling of 'convverted' to 'converted'.