From ea236d69700d69a7f81cee8d9917d3883d73aeb6 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Eirik=20Kol=C3=A5s?= Date: Fri, 1 Mar 2024 14:35:42 +0100 Subject: [PATCH] 3 bug vortexplottinggauss to ellipse is not exported correctly (#6) * changed cmakelists and ellipse class * package is successfully imported by other packages * Committing clang-format changes * fixed scaling factor in ellipse from gauss constructor * Committing clang-format changes * updated clang formatter workflow file --------- Co-authored-by: Clang Robot --- .github/workflows/clang-formatter.yml | 12 ++++++------ .../include/vortex_filtering/utils/ellipse.hpp | 16 ++++++++-------- vortex-filtering/src/utils/ellipse.cpp | 10 ++++++++-- 3 files changed, 22 insertions(+), 16 deletions(-) diff --git a/.github/workflows/clang-formatter.yml b/.github/workflows/clang-formatter.yml index 612029f3..f8643aa6 100644 --- a/.github/workflows/clang-formatter.yml +++ b/.github/workflows/clang-formatter.yml @@ -1,19 +1,19 @@ name: Run clang-format Linter on: - # push: - # branches: [ main ] + push: + branches: [ main ] workflow_dispatch: - pull_request: - types: [opened, reopened] - branches: [ main ] + # pull_request: + # types: [opened, reopened] + # branches: [ main ] jobs: build: runs-on: ubuntu-latest steps: - - uses: actions/checkout@v3 + - uses: actions/checkout@v4 - uses: DoozyX/clang-format-lint-action@v0.17 with: source: '.' diff --git a/vortex-filtering/include/vortex_filtering/utils/ellipse.hpp b/vortex-filtering/include/vortex_filtering/utils/ellipse.hpp index ea480249..705c17e0 100644 --- a/vortex-filtering/include/vortex_filtering/utils/ellipse.hpp +++ b/vortex-filtering/include/vortex_filtering/utils/ellipse.hpp @@ -22,16 +22,16 @@ namespace utils { class Ellipse { public: /** Construct a new Ellipse object - * @param center - * @param a - * @param b - * @param angle + * @param center center of the ellipse + * @param a half the length of the major axis (radius of the circumscribed circle) + * @param b half the length of the minor axis (radius of the inscribed circle) + * @param angle angle in radians */ Ellipse(const Eigen::Vector2d ¢er, double a, double b, double angle); /** Construct a new Ellipse object from a Gaussian - * @param gauss - * @param scale_factor + * @param gauss 2D Gaussian distribution + * @param scale_factor scale factor for the ellipse */ Ellipse(const vortex::prob::Gauss2d &gauss, double scale_factor = 1.0); @@ -50,12 +50,12 @@ class Ellipse { */ double y() const; - /** Get the a parameter of the ellipse + /** Get the a parameter of the ellipse (half the length of the major axis) * @return double */ double a() const; - /** Get the b parameter of the ellipse + /** Get the b parameter of the ellipse (half the length of the minor axis) * @return double */ double b() const; diff --git a/vortex-filtering/src/utils/ellipse.cpp b/vortex-filtering/src/utils/ellipse.cpp index 2cf6384a..aef09864 100644 --- a/vortex-filtering/src/utils/ellipse.cpp +++ b/vortex-filtering/src/utils/ellipse.cpp @@ -11,8 +11,14 @@ Ellipse::Ellipse(const vortex::prob::Gauss2d &gauss, double scale_factor) Eigen::Vector2d eigenValues = eigenSolver.eigenvalues(); Eigen::Matrix2d eigenVectors = eigenSolver.eigenvectors(); - a_ = scale_factor * sqrt(eigenValues(1)); - b_ = scale_factor * sqrt(eigenValues(0)); + // Sort eigenvalues in descending order + if (eigenValues(0) > eigenValues(1)) { + std::swap(eigenValues(0), eigenValues(1)); + eigenVectors.col(0).swap(eigenVectors.col(1)); + } + + a_ = sqrt(scale_factor * eigenValues(1)); + b_ = sqrt(scale_factor * eigenValues(0)); angle_ = atan2(eigenVectors(1, 1), eigenVectors(0, 1)); center_ = gauss.mean(); }