Control Libraries 6.3.4
Loading...
Searching...
No Matches
Public Member Functions | Static Public Member Functions | Friends | List of all members
state_representation::Ellipsoid Class Reference
Inheritance diagram for state_representation::Ellipsoid:
state_representation::Shape state_representation::State

Public Member Functions

 Ellipsoid ()
 Empty constructor. More...
 
 Ellipsoid (const std::string &name, const std::string &reference_frame="world")
 Constructor with name but empty state. More...
 
 Ellipsoid (const Ellipsoid &ellipsoid)
 Copy constructor from another ellipsoid. More...
 
Ellipsoidoperator= (const Ellipsoid &state)
 Copy assignment operator that have to be defined to the custom assignment operator. More...
 
const std::vector< double > & get_axis_lengths () const
 Getter of the axis lengths. More...
 
double get_axis_length (unsigned int index) const
 Getter of the axis length in one direction. More...
 
void set_axis_lengths (const std::vector< double > &axis_lengths)
 Setter of the axis lengths. More...
 
void set_axis_lengths (unsigned int index, double axis_length)
 Setter of the axis length at given index. More...
 
double get_rotation_angle () const
 Getter of the rotation angle. More...
 
void set_rotation_angle (double rotation_angle)
 Setter of the rotation angle. More...
 
const CartesianPose get_rotation () const
 
const std::list< CartesianPosesample_from_parameterization (unsigned int nb_samples) const
 Function to sample an obstacle from its parameterization. More...
 
const std::vector< double > to_std_vector () const
 Convert the ellipse to an std vector representation of its parameter. More...
 
virtual void set_data (const Eigen::VectorXd &data) override
 Set the ellipsoid data from an Eigen vector. More...
 
virtual void set_data (const std::vector< double > &data) override
 Set the ellipsoid data from a std vector. More...
 
- Public Member Functions inherited from state_representation::Shape
 Shape (const StateType &type)
 Constructor with a type. More...
 
 Shape (const StateType &type, const std::string &name, const std::string &reference_frame="world")
 Constructor with name but empty state. More...
 
 Shape (const Shape &shape)
 Copy constructor from another shape. More...
 
Shapeoperator= (const Shape &state)
 Copy assignment operator that have to be defined to the custom assignment operator. More...
 
const CartesianStateget_center_state () const
 Getter of the state. More...
 
const CartesianPoseget_center_pose () const
 Getter of the pose from the state. More...
 
const Eigen::Vector3d get_center_position () const
 Getter of the position from the state. More...
 
const Eigen::Quaterniond get_center_orientation () const
 Getter of the orientation from the state. More...
 
const CartesianTwistget_center_twist () const
 Getter of the twist from the state. More...
 
void set_center_state (const CartesianState &state)
 Setter of the state. More...
 
void set_center_pose (const CartesianPose &pose)
 Setter of the pose. More...
 
void set_center_position (const Eigen::Vector3d &position)
 Setter of the position. More...
 
void set_center_orientation (const Eigen::Quaterniond &orientation)
 Setter of the pose. More...
 
- Public Member Functions inherited from state_representation::State
 State ()
 Empty constructor. More...
 
 State (const StateType &type)
 Constructor only specifying the type of the state from the StateType enumeration. More...
 
 State (const StateType &type, const std::string &name, const bool &empty=true)
 Constructor with name specification. More...
 
 State (const State &state)
 Copy constructor from another State. More...
 
virtual ~State ()=default
 Virtual destructor.
 
Stateoperator= (const State &state)
 Copy assignment operator that have to be defined to the custom assignment operator. More...
 
const StateTypeget_type () const
 Getter of the type attribute. More...
 
bool is_empty () const
 Getter of the empty attribute. More...
 
void set_empty (bool empty=true)
 Setter of the empty attribute. More...
 
void set_filled ()
 Setter of the empty attribute to false and also reset the timestamp. More...
 
const std::chrono::time_point< std::chrono::steady_clock > & get_timestamp () const
 Getter of the timestamp attribute. More...
 
void set_timestamp (const std::chrono::time_point< std::chrono::steady_clock > &timepoint)
 Setter of the timestamp attribute. More...
 
void reset_timestamp ()
 Reset the timestamp attribute to now. More...
 
const std::string & get_name () const
 Getter of the name as const reference. More...
 
virtual void set_name (const std::string &name)
 Setter of the name. More...
 
template<typename DurationT >
bool is_deprecated (const std::chrono::duration< int64_t, DurationT > &time_delay)
 Check if the state is deprecated given a certain time delay. More...
 
virtual bool is_compatible (const State &state) const
 Check if the state is compatible for operations with the state given as argument. More...
 
virtual void initialize ()
 Initialize the State to a zero value. More...
 
virtual void set_data (const Eigen::VectorXd &data)
 Set the data of the state from a single Eigen vector. More...
 
virtual void set_data (const std::vector< double > &data)
 Set the data of the state from a single std vector. More...
 
virtual void set_data (const Eigen::MatrixXd &data)
 Set the data of the state from an Eigen matrix. More...
 
 operator bool () const noexcept
 Boolean operator for the truthiness of a state. More...
 

Static Public Member Functions

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. More...
 
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, A., et al. (1999). "Direct least square fitting of ellipses." IEEE Transactions on pattern analysis and machine intelligence 21(5) More...
 

Friends

std::ostream & operator<< (std::ostream &os, const Ellipsoid &ellipsoid)
 Overload the ostream operator for printing. More...
 

Additional Inherited Members

- Protected Member Functions inherited from state_representation::State
void set_type (const StateType &type)
 Override the state type. More...
 

Detailed Description

Definition at line 15 of file Ellipsoid.hpp.

Constructor & Destructor Documentation

◆ Ellipsoid() [1/3]

state_representation::Ellipsoid::Ellipsoid ( )

Empty constructor.

Definition at line 8 of file Ellipsoid.cpp.

◆ Ellipsoid() [2/3]

state_representation::Ellipsoid::Ellipsoid ( const std::string &  name,
const std::string &  reference_frame = "world" 
)
explicit

Constructor with name but empty state.

Parameters
namename of the ellipsoid
safety_marginthe safety_margin (default=0 in all axes)

Definition at line 10 of file Ellipsoid.cpp.

◆ Ellipsoid() [3/3]

state_representation::Ellipsoid::Ellipsoid ( const Ellipsoid ellipsoid)

Copy constructor from another ellipsoid.

Parameters
ellipsoidthe ellipsoid to copy

Definition at line 15 of file Ellipsoid.cpp.

Member Function Documentation

◆ fit()

const Ellipsoid state_representation::Ellipsoid::fit ( const std::string &  name,
const std::list< CartesianPose > &  points,
const std::string &  reference_frame = "world",
double  noise_level = 0.01 
)
static

Fit an ellipsoid on a set of points This method uses direct least square fitting from Fitzgibbon, A., et al. (1999). "Direct least square fitting of ellipses." IEEE Transactions on pattern analysis and machine intelligence 21(5)

Definition at line 85 of file Ellipsoid.cpp.

◆ from_algebraic_equation()

const Ellipsoid state_representation::Ellipsoid::from_algebraic_equation ( const std::string &  name,
const std::vector< double > &  coefficients,
const std::string &  reference_frame = "world" 
)
static

Compute an ellipsoid from its algebraic equation ax2 + bxy + cy2 + cx + ey + f.

Returns
the Ellipsoid in its geometric representation

Definition at line 39 of file Ellipsoid.cpp.

◆ get_axis_length()

double state_representation::Ellipsoid::get_axis_length ( unsigned int  index) const
inline

Getter of the axis length in one direction.

Parameters
indexthe index of the length (0 for x, 1 for y and 2 for z)
Returns
the length in the desired direction

Definition at line 149 of file Ellipsoid.hpp.

◆ get_axis_lengths()

const std::vector< double > & state_representation::Ellipsoid::get_axis_lengths ( ) const
inline

Getter of the axis lengths.

Returns
the axis lengths

Definition at line 145 of file Ellipsoid.hpp.

◆ get_rotation()

const CartesianPose state_representation::Ellipsoid::get_rotation ( ) const
inline

Definition at line 189 of file Ellipsoid.hpp.

◆ get_rotation_angle()

double state_representation::Ellipsoid::get_rotation_angle ( ) const
inline

Getter of the rotation angle.

Returns
the rotation angle

Definition at line 163 of file Ellipsoid.hpp.

◆ operator=()

Ellipsoid & state_representation::Ellipsoid::operator= ( const Ellipsoid state)
inline

Copy assignment operator that have to be defined to the custom assignment operator.

Parameters
statethe state with value to assign
Returns
reference to the current state with new values

Definition at line 138 of file Ellipsoid.hpp.

◆ sample_from_parameterization()

const std::list< CartesianPose > state_representation::Ellipsoid::sample_from_parameterization ( unsigned int  nb_samples) const

Function to sample an obstacle from its parameterization.

Parameters
nb_samplesthe number of sample points to generate
Returns
the list of sample points

Definition at line 18 of file Ellipsoid.cpp.

◆ set_axis_lengths() [1/2]

void state_representation::Ellipsoid::set_axis_lengths ( const std::vector< double > &  axis_lengths)
inline

Setter of the axis lengths.

Parameters
axis_lengthsthe new values

Definition at line 153 of file Ellipsoid.hpp.

◆ set_axis_lengths() [2/2]

void state_representation::Ellipsoid::set_axis_lengths ( unsigned int  index,
double  axis_length 
)
inline

Setter of the axis length at given index.

Parameters
indexthe desired index
axis_lengththe new length

Definition at line 158 of file Ellipsoid.hpp.

◆ set_data() [1/2]

void state_representation::Ellipsoid::set_data ( const Eigen::VectorXd &  data)
overridevirtual

Set the ellipsoid data from an Eigen vector.

Parameters
thedata vector with [center_position, rotation_angle, axis_lengths]

Reimplemented from state_representation::State.

Definition at line 168 of file Ellipsoid.cpp.

◆ set_data() [2/2]

void state_representation::Ellipsoid::set_data ( const std::vector< double > &  data)
overridevirtual

Set the ellipsoid data from a std vector.

Parameters
thedata vector with [center_position, rotation_angle, axis_lengths]

Reimplemented from state_representation::State.

Definition at line 181 of file Ellipsoid.cpp.

◆ set_rotation_angle()

void state_representation::Ellipsoid::set_rotation_angle ( double  rotation_angle)
inline

Setter of the rotation angle.

Parameters
rotation_anglethe rotation angle

Definition at line 167 of file Ellipsoid.hpp.

◆ to_std_vector()

const std::vector< double > state_representation::Ellipsoid::to_std_vector ( ) const
inline

Convert the ellipse to an std vector representation of its parameter.

Returns
an std vector with [center_position, rotation_angle, axis_lengths]

Definition at line 172 of file Ellipsoid.hpp.

Friends And Related Function Documentation

◆ operator<<

std::ostream & operator<< ( std::ostream &  os,
const Ellipsoid ellipsoid 
)
friend

Overload the ostream operator for printing.

Parameters
osthe ostream to append the string representing the Ellipsoid to
ellipsoidthe Ellipsoid to print
Returns
the appended ostream

Definition at line 185 of file Ellipsoid.cpp.


The documentation for this class was generated from the following files: