Skip to content

Commit

Permalink
3 bug vortexplottinggauss to ellipse is not exported correctly (#6)
Browse files Browse the repository at this point in the history
* 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 <[email protected]>
  • Loading branch information
EirikKolas and Clang Robot authored Mar 1, 2024
1 parent e6d7487 commit ea236d6
Show file tree
Hide file tree
Showing 3 changed files with 22 additions and 16 deletions.
12 changes: 6 additions & 6 deletions .github/workflows/clang-formatter.yml
Original file line number Diff line number Diff line change
@@ -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/[email protected]
with:
source: '.'
Expand Down
16 changes: 8 additions & 8 deletions vortex-filtering/include/vortex_filtering/utils/ellipse.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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 &center, 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);

Expand All @@ -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;
Expand Down
10 changes: 8 additions & 2 deletions vortex-filtering/src/utils/ellipse.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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();
}
Expand Down

0 comments on commit ea236d6

Please sign in to comment.