1#include "state_representation/geometry/Ellipsoid.hpp" 
    2#include "state_representation/exceptions/NoSolutionToFitException.hpp" 
    3#include "state_representation/exceptions/IncompatibleSizeException.hpp" 
    5#include "state_representation/exceptions/EmptyStateException.hpp" 
   11    Shape(
StateType::GEOMETRY_ELLIPSOID, name, reference_frame), axis_lengths_({1., 1.}), rotation_angle_(0) {
 
   16    Shape(ellipsoid), axis_lengths_(ellipsoid.axis_lengths_), rotation_angle_(0) {}
 
   23  std::vector<double> alpha = math_tools::linspace(0, 2 * M_PI, nb_samples);
 
   25  std::list<CartesianPose> samples;
 
   26  for (
unsigned int i = 0; i < nb_samples; ++i) {
 
   28    double a = alpha.at(i);
 
   29    Eigen::Vector3d position;
 
   34    samples.push_back(this->
get_center_pose() * this->get_rotation() * point);
 
   40    const std::string& name, 
const std::vector<double>& coefficients, 
const std::string& reference_frame
 
   43  double b2 = coefficients[1] * coefficients[1];
 
   44  double delta = b2 - 4 * coefficients[0] * coefficients[2];
 
   47  double tmp1 = coefficients[0] * coefficients[4] * coefficients[4] 
 
   48      + coefficients[2] * coefficients[3] * coefficients[3] 
 
   49      - coefficients[1] * coefficients[3] * coefficients[4] 
 
   50      + delta * coefficients[5]; 
 
   51  double tmp2 = coefficients[2] - coefficients[0]; 
 
   52  double tmp3 = sqrt(tmp2 * tmp2 + b2);
 
   56  std::vector<double> axis_lengths(2);
 
   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;
 
   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;
 
   72  if (abs(coefficients[1]) > 1e-4) {
 
   73    phi = atan2(tmp2 - tmp3, coefficients[1]);
 
   74  } 
else if (coefficients[0] < coefficients[2]) {
 
   79  if (r1 < r2) { phi += M_PI_2; }
 
   86    const std::string& name, 
const std::list<CartesianPose>& points, 
const std::string& reference_frame,
 
   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;
 
   96  size_t nb_points = points.size();
 
   97  Eigen::VectorXd x_value(nb_points);
 
   98  Eigen::VectorXd y_value(nb_points);
 
  102  std::vector<double> coefficients(6);
 
  103  Eigen::GeneralizedEigenSolver<Eigen::Matrix<double, 6, 6>> solver;
 
  105  std::default_random_engine generator;
 
  106  std::normal_distribution<double> 
dist(0., noise_level);
 
  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);
 
  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;
 
  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);
 
  132    Eigen::Matrix<double, 6, 6> scatter_matrix = design_matrix.transpose() * design_matrix;
 
  135    solver.compute(scatter_matrix, constraint_matrix);
 
  138    unsigned int solution_index;
 
  139    double eigenvalue = solver.betas().maxCoeff(&solution_index);
 
  142    if (eigenvalue < 0) {
 
  147    Eigen::VectorXd solution = solver.eigenvectors().col(solution_index).real();
 
  152    double sx2 = sx * sx;
 
  153    double sy2 = sy * sy;
 
  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;
 
  163    delta = coefficients[1] * coefficients[1] - 4 * coefficients[0] * coefficients[2];
 
  172  if (data.size() != 6) {
 
  174        "Input is of incorrect size: expected 6, given " + std::to_string(data.size()));
 
  182  this->
set_data(Eigen::VectorXd::Map(data.data(), data.size()));
 
  186  if (ellipsoid.is_empty()) {
 
  187    os << 
"Empty Ellipsoid";
 
  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();
 
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.
void set_rotation_angle(double rotation_angle)
Setter of the rotation angle.
double get_axis_length(unsigned int index) const
Getter of the axis length in one direction.
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.
const std::list< CartesianPose > sample_from_parameterization(unsigned int nb_samples) const
Function to sample an obstacle from its parameterization.
void set_axis_lengths(const std::vector< double > &axis_lengths)
Setter of the axis lengths.
Ellipsoid()
Empty constructor.
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,...
const CartesianState & get_center_state() const
Getter of the state.
const CartesianPose & get_center_pose() const
Getter of the pose from the state.
void set_center_position(const Eigen::Vector3d &position)
Setter of the position.
const std::string & get_name() const
Getter of the name as const reference.
void set_filled()
Setter of the empty attribute to false and also reset the timestamp.
bool is_empty() const
Getter of the empty attribute.
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)
StateType
The class types inheriting from State.