Control Libraries 6.3.4
Loading...
Searching...
No Matches
Ellipsoid.cpp
1#include "state_representation/geometry/Ellipsoid.hpp"
2#include "state_representation/exceptions/NoSolutionToFitException.hpp"
3#include "state_representation/exceptions/IncompatibleSizeException.hpp"
4
5#include "state_representation/exceptions/EmptyStateException.hpp"
6
7namespace state_representation {
8Ellipsoid::Ellipsoid() : Shape(StateType::GEOMETRY_ELLIPSOID), axis_lengths_({1., 1.}), rotation_angle_(0) {}
9
10Ellipsoid::Ellipsoid(const std::string& name, const std::string& reference_frame) :
11 Shape(StateType::GEOMETRY_ELLIPSOID, name, reference_frame), axis_lengths_({1., 1.}), rotation_angle_(0) {
12 this->set_filled();
13}
14
16 Shape(ellipsoid), axis_lengths_(ellipsoid.axis_lengths_), rotation_angle_(0) {}
17
18const std::list<CartesianPose> Ellipsoid::sample_from_parameterization(unsigned int nb_samples) const {
19 if (this->get_center_state().is_empty()) {
20 throw exceptions::EmptyStateException("The center state of the Ellipsoid is not set yet.");
21 }
22 // use a linspace to have a full rotation angle between [0, 2pi]
23 std::vector<double> alpha = math_tools::linspace(0, 2 * M_PI, nb_samples);
24
25 std::list<CartesianPose> samples;
26 for (unsigned int i = 0; i < nb_samples; ++i) {
27 CartesianPose point(this->get_name() + "_point" + std::to_string(i), this->get_rotation().get_name());
28 double a = alpha.at(i);
29 Eigen::Vector3d position;
30 position(0) = this->get_axis_length(0) * cos(a);
31 position(1) = this->get_axis_length(1) * sin(a);
32 position(2) = 0;
33 point.set_position(position);
34 samples.push_back(this->get_center_pose() * this->get_rotation() * point);
35 }
36 return samples;
37}
38
40 const std::string& name, const std::vector<double>& coefficients, const std::string& reference_frame
41) {
42 // extract all the components from the coefficients vector
43 double b2 = coefficients[1] * coefficients[1];
44 double delta = b2 - 4 * coefficients[0] * coefficients[2];
45
46 // store intermediate calculations
47 double tmp1 = coefficients[0] * coefficients[4] * coefficients[4] // AE2
48 + coefficients[2] * coefficients[3] * coefficients[3] // CD2
49 - coefficients[1] * coefficients[3] * coefficients[4] // BDE
50 + delta * coefficients[5]; // deltaF
51 double tmp2 = coefficients[2] - coefficients[0]; // C-A
52 double tmp3 = sqrt(tmp2 * tmp2 + b2);
53
54 // create the ellipsoid in the plan and set its center and axis
55 Ellipsoid result(name, reference_frame);
56 std::vector<double> axis_lengths(2);
57
58 // set axis lengths
59 double r1 = -sqrt(2 * tmp1 * (coefficients[0] + coefficients[2] + tmp3)) / delta;
60 double r2 = -sqrt(2 * tmp1 * (coefficients[0] + coefficients[2] - tmp3)) / delta;
61 axis_lengths[0] = (r1 >= r2) ? r1 : r2;
62 axis_lengths[1] = (r1 >= r2) ? r2 : r1;
63 result.set_axis_lengths(axis_lengths);
64
65 // set center position
66 double cx = (2 * coefficients[2] * coefficients[3] - coefficients[1] * coefficients[4]) / delta;
67 double cy = (2 * coefficients[0] * coefficients[4] - coefficients[1] * coefficients[3]) / delta;
68 result.set_center_position(Eigen::Vector3d(cx, cy, 0));
69
70 // set center orientation
71 double phi;
72 if (abs(coefficients[1]) > 1e-4) {
73 phi = atan2(tmp2 - tmp3, coefficients[1]);
74 } else if (coefficients[0] < coefficients[2]) {
75 phi = 0.;
76 } else {
77 phi = M_PI_2;
78 }
79 if (r1 < r2) { phi += M_PI_2; }
80 result.set_rotation_angle(phi);
81
82 return result;
83}
84
86 const std::string& name, const std::list<CartesianPose>& points, const std::string& reference_frame,
87 double noise_level
88) {
89 // define the constraint matrix
90 Eigen::SparseMatrix<double> constraint_matrix(6, 6);
91 constraint_matrix.insert(1, 1) = -1;
92 constraint_matrix.insert(0, 2) = 2;
93 constraint_matrix.insert(2, 0) = 2;
94
95 // preprocessing normalize the data TODO using PCA to find the plan
96 size_t nb_points = points.size();
97 Eigen::VectorXd x_value(nb_points);
98 Eigen::VectorXd y_value(nb_points);
99
100 // retry with noise everytime delta > 0
101 double delta;
102 std::vector<double> coefficients(6);
103 Eigen::GeneralizedEigenSolver<Eigen::Matrix<double, 6, 6>> solver;
104
105 std::default_random_engine generator;
106 std::normal_distribution<double> dist(0., noise_level);
107 do {
108 unsigned int i = 0;
109 for (const auto& p: points) {
110 x_value[i] = p.get_position()(0) + dist(generator);
111 y_value[i] = p.get_position()(1) + dist(generator);
112 ++i;
113 }
114
115 double xm = x_value.mean();
116 double ym = y_value.mean();
117 double sx = 0.5 * (x_value.maxCoeff() - x_value.minCoeff());
118 double sy = 0.5 * (y_value.maxCoeff() - y_value.minCoeff());
119 Eigen::VectorXd x_value_centered = (x_value.array() - xm) / sx;
120 Eigen::VectorXd y_value_centered = (y_value.array() - ym) / sy;
121
122 // compute the design matrix
123 Eigen::MatrixXd design_matrix(nb_points, 6);
124 design_matrix.col(0) = x_value_centered.array() * x_value_centered.array();
125 design_matrix.col(1) = x_value_centered.array() * y_value_centered.array();
126 design_matrix.col(2) = y_value_centered.array() * y_value_centered.array();
127 design_matrix.col(3) = x_value_centered;
128 design_matrix.col(4) = y_value_centered;
129 design_matrix.col(5) = Eigen::VectorXd::Ones(nb_points);
130
131 // compute the scatter matrix
132 Eigen::Matrix<double, 6, 6> scatter_matrix = design_matrix.transpose() * design_matrix;
133
134 // solve the generalized eigenvalue problem
135 solver.compute(scatter_matrix, constraint_matrix);
136
137 // solution correspon to the single positive eigenvalue
138 unsigned int solution_index;
139 double eigenvalue = solver.betas().maxCoeff(&solution_index);
140
141 // no solution case
142 if (eigenvalue < 0) {
143 throw exceptions::NoSolutionToFitException("No solution found for the ellipse fitting");
144 }
145
146 // extract the solution
147 Eigen::VectorXd solution = solver.eigenvectors().col(solution_index).real();
148
149 // unnormalize the parameters TODO inverse PCA
150 double kx = xm;
151 double ky = ym;
152 double sx2 = sx * sx;
153 double sy2 = sy * sy;
154
155 coefficients[0] = solution(0) * sy2;
156 coefficients[1] = solution(1) * sx * sy;
157 coefficients[2] = solution(2) * sx2;
158 coefficients[3] = -2 * solution(0) * sy2 * kx - solution(1) * sx * sy * ky + solution(3) * sx * sy2;
159 coefficients[4] = -solution(1) * sx * sy * kx - 2 * solution(2) * sx2 * ky + solution(4) * sx2 * sy;
160 coefficients[5] = solution(0) * sy2 * kx * kx + solution(1) * sx * sy * kx * ky + solution(2) * sx2 * ky * ky
161 - solution(3) * sx * sy2 * kx - solution(4) * sx2 * sy * ky + solution(5) * sx2 * sy2;
162
163 delta = coefficients[1] * coefficients[1] - 4 * coefficients[0] * coefficients[2];
164 } while (delta > 0);
165 return from_algebraic_equation(name, coefficients, reference_frame);
166}
167
168void Ellipsoid::set_data(const Eigen::VectorXd& data) {
169 if (this->get_center_state().is_empty()) {
170 throw exceptions::EmptyStateException("The center state of the Ellipsoid is not set yet.");
171 }
172 if (data.size() != 6) {
174 "Input is of incorrect size: expected 6, given " + std::to_string(data.size()));
175 }
176 this->set_center_position(data.head(3));
177 this->set_rotation_angle(data(3));
178 this->set_axis_lengths({data(4), data(5)});
179}
180
181void Ellipsoid::set_data(const std::vector<double>& data) {
182 this->set_data(Eigen::VectorXd::Map(data.data(), data.size()));
183}
184
185std::ostream& operator<<(std::ostream& os, const Ellipsoid& ellipsoid) {
186 if (ellipsoid.is_empty()) {
187 os << "Empty Ellipsoid";
188 } else {
189 os << "Ellipsoid " << ellipsoid.get_name() << " of dimensions [";
190 os << ellipsoid.get_axis_length(0) << ", ";
191 os << ellipsoid.get_axis_length(1) << "]";
192 os << " with state:" << std::endl;
193 os << ellipsoid.get_center_state();
194 }
195 return os;
196}
197}
Class to define CartesianPose in cartesian space as 3D position and quaternion based orientation.
void set_position(const Eigen::Vector3d &position)
Setter of the position.
virtual void set_data(const Eigen::VectorXd &data) override
Set the ellipsoid data from an Eigen vector.
Definition: Ellipsoid.cpp:168
void set_rotation_angle(double rotation_angle)
Setter of the rotation angle.
Definition: Ellipsoid.hpp:167
double get_axis_length(unsigned int index) const
Getter of the axis length in one direction.
Definition: Ellipsoid.hpp:149
static const Ellipsoid from_algebraic_equation(const std::string &name, const std::vector< double > &coefficients, const std::string &reference_frame="world")
Compute an ellipsoid from its algebraic equation ax2 + bxy + cy2 + cx + ey + f.
Definition: Ellipsoid.cpp:39
const std::list< CartesianPose > sample_from_parameterization(unsigned int nb_samples) const
Function to sample an obstacle from its parameterization.
Definition: Ellipsoid.cpp:18
void set_axis_lengths(const std::vector< double > &axis_lengths)
Setter of the axis lengths.
Definition: Ellipsoid.hpp:153
Ellipsoid()
Empty constructor.
Definition: Ellipsoid.cpp:8
static const Ellipsoid fit(const std::string &name, const std::list< CartesianPose > &points, const std::string &reference_frame="world", double noise_level=0.01)
Fit an ellipsoid on a set of points This method uses direct least square fitting from Fitzgibbon,...
Definition: Ellipsoid.cpp:85
const CartesianState & get_center_state() const
Getter of the state.
Definition: Shape.hpp:117
const CartesianPose & get_center_pose() const
Getter of the pose from the state.
Definition: Shape.hpp:121
void set_center_position(const Eigen::Vector3d &position)
Setter of the position.
Definition: Shape.hpp:150
const std::string & get_name() const
Getter of the name as const reference.
Definition: State.cpp:48
void set_filled()
Setter of the empty attribute to false and also reset the timestamp.
Definition: State.cpp:31
bool is_empty() const
Getter of the empty attribute.
Definition: State.cpp:23
Core state variables and objects.
double dist(const CartesianState &s1, const CartesianState &s2, const CartesianStateVariable &state_variable_type=CartesianStateVariable::ALL)
compute the distance between two CartesianStates
std::ostream & operator<<(std::ostream &os, const Ellipsoid &ellipsoid)
Definition: Ellipsoid.cpp:185
StateType
The class types inheriting from State.
Definition: StateType.hpp:13