diff --git a/include/ale.h b/include/ale.h index ff1810f5697d0b15b25c5a2c38cd95bd2dd6e80a..7145e753bebafcd35bef6464c3f68fd0a90b0c4c 100644 --- a/include/ale.h +++ b/include/ale.h @@ -34,10 +34,9 @@ namespace ale { std::vector times, double time, interpolation interp); - std::vector getRotation(std::string from, std::string to, - std::vector coefficients, double time); - std::vector getAngularVelocity(std::string from, std::string to, - std::vector coefficients, double time); + std::vector getRotation(std::vector> coeffs, double time); + std::vector getAngularVelocity(std::vector> coeffs, double time); + double evaluatePolynomial(std::vector coeffs, double time, int d); double interpolate(std::vector points, std::vector times, double time, interpolation interp, int d); std::string load(std::string filename); diff --git a/src/ale.cpp b/src/ale.cpp index 6e139f71396000f6acf56c63b0e481ea5b9dbcc3..5427e9203f97a299706cf4f411d53816daeaddb7 100644 --- a/src/ale.cpp +++ b/src/ale.cpp @@ -174,16 +174,52 @@ namespace ale { } // Rotation Function Functions - vector getRotation(string from, string to, - vector coefficients, double time) { - vector coordinate = {0.0, 0.0, 0.0}; - return coordinate; + std::vector getRotation(vector> coeffs, double time) { + + if (coeffs.size() != 3) { + throw invalid_argument("Invalid input coefficients, expected three vectors."); + } + + vector rotation = {0.0, 0.0, 0.0}; + + rotation[0] = evaluatePolynomial(coeffs[0], time, 0); // X + rotation[1] = evaluatePolynomial(coeffs[1], time, 0); // Y + rotation[2] = evaluatePolynomial(coeffs[2], time, 0); // Z + + Eigen::Quaterniond quat; + quat = Eigen::AngleAxisd(rotation[0] * M_PI / 180, Eigen::Vector3d::UnitZ()) + * Eigen::AngleAxisd(rotation[1] * M_PI / 180, Eigen::Vector3d::UnitX()) + * Eigen::AngleAxisd(rotation[2] * M_PI / 180, Eigen::Vector3d::UnitZ()); + + quat.normalize(); + + vector rotationQ = {quat.w(), quat.x(), quat.y(), quat.z()}; + return rotationQ; } - vector getAngularVelocity(string from, string to, - vector coefficients, double time) { - vector coordinate = {0.0, 0.0, 0.0}; - return coordinate; + vector getAngularVelocity(vector> coeffs, double time) { + + if (coeffs.size() != 3) { + throw invalid_argument("Invalid input coefficients, expected three vectors."); + } + + double phi = evaluatePolynomial(coeffs[0], time, 0); // X + double theta = evaluatePolynomial(coeffs[1], time, 0); // Y + double psi = evaluatePolynomial(coeffs[2], time, 0); // Z + + double phi_dt = evaluatePolynomial(coeffs[0], time, 1); + double theta_dt = evaluatePolynomial(coeffs[1], time, 1); + double psi_dt = evaluatePolynomial(coeffs[2], time, 1); + + Eigen::Quaterniond quat1, quat2; + quat1 = Eigen::AngleAxisd(phi * M_PI / 180, Eigen::Vector3d::UnitZ()); + quat2 = Eigen::AngleAxisd(theta * M_PI / 180, Eigen::Vector3d::UnitX()); + + Eigen::Vector3d velocity = phi_dt * Eigen::Vector3d::UnitZ(); + velocity += theta_dt * (quat1 * Eigen::Vector3d::UnitX()); + velocity += psi_dt * (quat1 * quat2 * Eigen::Vector3d::UnitZ()); + + return {velocity[0], velocity[1], velocity[2]}; } // Polynomial evaluation helper function diff --git a/tests/ctests/AleTest.cpp b/tests/ctests/AleTest.cpp index bb9f083e01c6f93e4d4d1e0be446257a9079a527..6131c4e526b74b9331cbb87424338f89160f97a3 100644 --- a/tests/ctests/AleTest.cpp +++ b/tests/ctests/AleTest.cpp @@ -236,6 +236,48 @@ TEST(VelocityCoeffTest, InvalidInput) { EXPECT_THROW(ale::getVelocity(invalid_coeffs_sizes, valid_time), invalid_argument); } +TEST(RotationCoeffTest, ZeroOrderPolynomial) { + double time = 1.0; + vector> coeffs = {{90}, + {0}, + {0}}; + + vector coordinate = ale::getRotation(coeffs, time); + + ASSERT_EQ(4, coordinate.size()); + EXPECT_DOUBLE_EQ(1 / sqrt(2), coordinate[0]); + EXPECT_DOUBLE_EQ(0, coordinate[1]); + EXPECT_DOUBLE_EQ(0, coordinate[2]); + EXPECT_DOUBLE_EQ(1 / sqrt(2), coordinate[3]); +} + +TEST(RotationCoeffTest, InvalidInput) { + double time = 1.0; + vector> coeffs = {{90}, + {0}}; + + EXPECT_THROW(ale::getRotation(coeffs, time), invalid_argument); +} + +TEST(AngularVelocityCoeffTest, DefaultAngularExample) { + vector> coeffs = {{0, 90}, {0, 90}, {0, 90}}; + double time = 1.0; + + vector av = ale::getAngularVelocity(coeffs, time); + + ASSERT_EQ(3, av.size()); + EXPECT_DOUBLE_EQ(90, av[0]); + EXPECT_DOUBLE_EQ(90, av[1]); + EXPECT_DOUBLE_EQ(90, av[2]); +} + +TEST(AngularVelocityCoeffTest, InvalidInput) { + vector> coeffs = {{0, 90}, {0, 90}}; + double time = 2.0; + + EXPECT_THROW(ale::getAngularVelocity(coeffs, time), invalid_argument); +} + TEST(RotationInterpTest, ExampleGetRotation) { // simple test, only checks if API hit correctly and output is normalized