Control Libraries 7.4.0
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.
 
 Ellipsoid (const std::string &name, const std::string &reference_frame="world")
 Constructor with name and reference frame.
 
 Ellipsoid (const Ellipsoid &ellipsoid)
 Copy constructor from another Ellipsoid.
 
Ellipsoidoperator= (const Ellipsoid &state)
 Copy assignment operator that has to be defined to the custom assignment operator.
 
const std::vector< double > & get_axis_lengths () const
 Getter of the axis lengths.
 
double get_axis_length (unsigned int index) const
 Getter of the axis length in one direction.
 
double get_rotation_angle () const
 Getter of the rotation angle.
 
const CartesianPose get_rotation () const
 Getter of the rotation as a pose.
 
void set_axis_lengths (const std::vector< double > &axis_lengths)
 Setter of the axis lengths.
 
void set_axis_lengths (unsigned int index, double axis_length)
 Setter of the axis length at given index.
 
void set_rotation_angle (double rotation_angle)
 Setter of the rotation angle.
 
void set_data (const Eigen::VectorXd &data) override
 Set the ellipsoid data from an Eigen vector.
 
void set_data (const std::vector< double > &data) override
 Set the ellipsoid data from a std vector.
 
const std::list< CartesianPosesample_from_parameterization (unsigned int nb_samples) const
 Function to sample an obstacle from its parameterization.
 
const std::vector< double > to_std_vector () const
 Convert the Ellipsoid to an std vector representation of its parameter.
 
- Public Member Functions inherited from state_representation::Shape
 Shape ()
 Empty constructor.
 
 Shape (const std::string &name, const std::string &reference_frame="world")
 Constructor with name and reference frame.
 
 Shape (const Shape &shape)
 Copy constructor from another Shape.
 
Shapeoperator= (const Shape &state)
 Copy assignment operator that has to be defined to the custom assignment operator.
 
const CartesianStateget_center_state () const
 Getter of the state.
 
const CartesianPoseget_center_pose () const
 Getter of the pose from the state.
 
const Eigen::Vector3d get_center_position () const
 Getter of the position from the state.
 
const Eigen::Quaterniond get_center_orientation () const
 Getter of the orientation from the state.
 
const CartesianTwistget_center_twist () const
 Getter of the twist from the state.
 
void set_center_state (const CartesianState &state)
 Setter of the state.
 
void set_center_pose (const CartesianPose &pose)
 Setter of the pose.
 
void set_center_position (const Eigen::Vector3d &position)
 Setter of the position.
 
void set_center_orientation (const Eigen::Quaterniond &orientation)
 Setter of the pose.
 
- Public Member Functions inherited from state_representation::State
 State ()
 Empty constructor.
 
 State (const std::string &name)
 Constructor with name specification.
 
 State (const State &state)
 Copy constructor from another state.
 
virtual ~State ()=default
 Virtual destructor.
 
Stateoperator= (const State &state)
 Copy assignment operator that has to be defined to the custom assignment operator.
 
const StateTypeget_type () const
 Getter of the type attribute.
 
const std::string & get_name () const
 Getter of the name attribute.
 
bool is_empty () const
 Getter of the empty attribute.
 
const std::chrono::time_point< std::chrono::steady_clock > & get_timestamp () const
 Getter of the timestamp attribute.
 
virtual void set_name (const std::string &name)
 Setter of the name attribute.
 
void reset_timestamp ()
 Reset the timestamp attribute to now.
 
virtual void set_data (const Eigen::MatrixXd &data)
 Set the data of the state from an Eigen matrix.
 
double get_age () const
 Get the age of the state, i.e. the time since the last modification.
 
virtual bool is_incompatible (const State &state) const
 Check if the state is incompatible for operations with the state given as argument.
 
bool is_deprecated (double time_delay) const
 Check if the state is deprecated given a certain time delay.
 
template<typename DurationT >
bool is_deprecated (const std::chrono::duration< int64_t, DurationT > &time_delay) const
 Check if the state is deprecated given a certain time delay.
 
virtual void reset ()
 Reset the object to a post-construction state.
 
 operator bool () const noexcept
 Boolean operator for the truthiness of a state.
 

Static Public Member Functions

static Ellipsoid Unit (const std::string &name, const std::string &reference_frame="world")
 Constructor for a Ellipsoid with identity state, unit axis lengths and zero rotation angle.
 
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)
 
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.
 
- Static Public Member Functions inherited from state_representation::Shape
static Shape Unit (const std::string &name, const std::string &reference_frame="world")
 Constructor for a Shape with identity state.
 

Friends

void swap (Ellipsoid &state1, Ellipsoid &state2)
 Swap the values of the two Ellipsoids.
 
std::ostream & operator<< (std::ostream &os, const Ellipsoid &ellipsoid)
 Overload the ostream operator for printing.
 

Additional Inherited Members

- Protected Member Functions inherited from state_representation::Shape
std::string to_string () const override
 Convert the state to its string representation.
 
- Protected Member Functions inherited from state_representation::State
void set_type (const StateType &type)
 Setter of the state type attribute.
 
void set_empty (bool empty=true)
 Setter of the empty attribute.
 
void assert_not_empty () const
 Throw an exception if the state is empty.
 

Detailed Description

Definition at line 12 of file Ellipsoid.hpp.

Constructor & Destructor Documentation

◆ Ellipsoid() [1/3]

state_representation::Ellipsoid::Ellipsoid ( )

Empty constructor.

Definition at line 12 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 and reference frame.

Parameters
nameName of the Ellipsoid and its state
reference_frameThe reference frame in which the state is expressed (default is "world")

Definition at line 16 of file Ellipsoid.cpp.

◆ Ellipsoid() [3/3]

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

Copy constructor from another Ellipsoid.

Parameters
shapeThe Ellipsoid to copy from

Definition at line 21 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 93 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 176 of file Ellipsoid.cpp.

◆ get_axis_length()

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

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 46 of file Ellipsoid.cpp.

◆ get_axis_lengths()

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

Getter of the axis lengths.

Returns
The axis lengths

Definition at line 41 of file Ellipsoid.cpp.

◆ get_rotation()

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

Getter of the rotation as a pose.

Definition at line 56 of file Ellipsoid.cpp.

◆ get_rotation_angle()

double state_representation::Ellipsoid::get_rotation_angle ( ) const

Getter of the rotation angle.

Returns
The rotation angle

Definition at line 51 of file Ellipsoid.cpp.

◆ operator=()

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

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

Parameters
stateThe Ellipsoid with value to assign
Returns
Reference to the current Ellipsoid with new values

Definition at line 35 of file Ellipsoid.cpp.

◆ 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 222 of file Ellipsoid.cpp.

◆ set_axis_lengths() [1/2]

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

Setter of the axis lengths.

Parameters
axis_lengthsThe new values

Definition at line 64 of file Ellipsoid.cpp.

◆ set_axis_lengths() [2/2]

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

Setter of the axis length at given index.

Parameters
indexThe desired index
axis_lengthThe new length

Definition at line 69 of file Ellipsoid.cpp.

◆ 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 79 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 89 of file Ellipsoid.cpp.

◆ set_rotation_angle()

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

Setter of the rotation angle.

Parameters
rotation_angleThe rotation angle

Definition at line 74 of file Ellipsoid.cpp.

◆ to_std_vector()

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

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

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

Definition at line 243 of file Ellipsoid.cpp.

◆ Unit()

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

Constructor for a Ellipsoid with identity state, unit axis lengths and zero rotation angle.

Parameters
nameName of the Ellipsoid and its state
reference_frameThe reference frame in which the state is expressed (default is "world")

Definition at line 29 of file Ellipsoid.cpp.

Friends And Related Symbol 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 state
stateThe state to print
Returns
The appended ostream

Definition at line 258 of file Ellipsoid.cpp.

◆ swap

void swap ( Ellipsoid state1,
Ellipsoid state2 
)
friend

Swap the values of the two Ellipsoids.

Parameters
state1Ellipsoid to be swapped with 2
state2Ellipsoid to be swapped with 1

Definition at line 153 of file Ellipsoid.hpp.


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