Control Libraries 6.3.4
|
Public Member Functions | |
Trajectory () | |
Empty constructor. More... | |
Trajectory (const std::string &name) | |
Constructor with name and reference frame provided. More... | |
const std::string | get_reference_frame () const |
Getter of the reference frame as const reference. More... | |
virtual void | set_reference_frame (const std::string &reference_frame) |
Setter of the reference frame. More... | |
const std::vector< std::string > & | get_joint_names () const |
Getter of the names attribute. More... | |
void | set_joint_names (unsigned int nb_joints) |
Setter of the names attribute from the number of joints. More... | |
void | set_joint_names (const std::vector< std::string > &joint_names) |
Setter of the names attribute from the joints names. More... | |
void | initialize () |
Initialize trajectory. More... | |
template<typename DurationT > | |
void | add_point (const StateT &new_point, const std::chrono::duration< int64_t, DurationT > &new_time) |
Add new point and corresponding time to trajectory. More... | |
template<typename DurationT > | |
void | insert_point (const StateT &new_point, const std::chrono::duration< int64_t, DurationT > &new_time, int pos) |
Insert new point and corresponding time to trajectory between two already existing points. More... | |
void | delete_point () |
Delete last point and corresponding time from trajectory. More... | |
void | clear () |
Clear trajectory. More... | |
const std::deque< StateT > & | get_points () const |
Get attribute list of trajectory points. More... | |
const StateT & | get_point (unsigned int index) const |
Get the trajectory point at given index. More... | |
StateT & | get_point (unsigned int index) |
Get the trajectory point at given index. More... | |
const std::deque< std::chrono::nanoseconds > & | get_times () const |
Get attribute list of trajectory times. More... | |
int | get_size () const |
Get attribute number of point in trajectory. More... | |
const std::pair< StateT, std::chrono::nanoseconds > | operator[] (unsigned int idx) const |
Operator overload for returning a single trajectory point and corresponding time. More... | |
std::pair< StateT, std::chrono::nanoseconds > | operator[] (unsigned int idx) |
Operator overload for returning a single trajectory point and corresponding time. 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. | |
State & | operator= (const State &state) |
Copy assignment operator that have to be defined to the custom assignment operator. More... | |
const StateType & | get_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... | |
Additional Inherited Members | |
Protected Member Functions inherited from state_representation::State | |
void | set_type (const StateType &type) |
Override the state type. More... | |
Definition at line 9 of file Trajectory.hpp.
|
explicit |
Empty constructor.
Definition at line 120 of file Trajectory.hpp.
|
explicit |
Constructor with name and reference frame provided.
name the name of the state
Definition at line 126 of file Trajectory.hpp.
void state_representation::Trajectory< StateT >::add_point | ( | const StateT & | new_point, |
const std::chrono::duration< int64_t, DurationT > & | new_time | ||
) |
Add new point and corresponding time to trajectory.
Definition at line 169 of file Trajectory.hpp.
void state_representation::Trajectory< StateT >::clear |
Clear trajectory.
Definition at line 215 of file Trajectory.hpp.
void state_representation::Trajectory< StateT >::delete_point |
Delete last point and corresponding time from trajectory.
Definition at line 204 of file Trajectory.hpp.
|
inline |
Getter of the names attribute.
Definition at line 143 of file Trajectory.hpp.
StateT & state_representation::Trajectory< StateT >::get_point | ( | unsigned int | index | ) |
Get the trajectory point at given index.
index | the index |
Definition at line 231 of file Trajectory.hpp.
const StateT & state_representation::Trajectory< StateT >::get_point | ( | unsigned int | index | ) | const |
Get the trajectory point at given index.
index | the index |
Definition at line 226 of file Trajectory.hpp.
|
inline |
Get attribute list of trajectory points.
Definition at line 221 of file Trajectory.hpp.
|
inline |
Getter of the reference frame as const reference.
Definition at line 133 of file Trajectory.hpp.
int state_representation::Trajectory< StateT >::get_size |
Get attribute number of point in trajectory.
Definition at line 241 of file Trajectory.hpp.
|
inline |
Get attribute list of trajectory times.
Definition at line 236 of file Trajectory.hpp.
|
virtual |
Initialize trajectory.
Reimplemented from state_representation::State.
Definition at line 161 of file Trajectory.hpp.
void state_representation::Trajectory< StateT >::insert_point | ( | const StateT & | new_point, |
const std::chrono::duration< int64_t, DurationT > & | new_time, | ||
int | pos | ||
) |
Insert new point and corresponding time to trajectory between two already existing points.
Definition at line 183 of file Trajectory.hpp.
std::pair< StateT, std::chrono::nanoseconds > state_representation::Trajectory< StateT >::operator[] | ( | unsigned int | idx | ) |
Operator overload for returning a single trajectory point and corresponding time.
Definition at line 251 of file Trajectory.hpp.
const std::pair< StateT, std::chrono::nanoseconds > state_representation::Trajectory< StateT >::operator[] | ( | unsigned int | idx | ) | const |
Operator overload for returning a single trajectory point and corresponding time.
Definition at line 246 of file Trajectory.hpp.
|
inline |
Setter of the names attribute from the joints names.
Definition at line 156 of file Trajectory.hpp.
|
inline |
Setter of the names attribute from the number of joints.
Definition at line 148 of file Trajectory.hpp.
|
inlinevirtual |
Setter of the reference frame.
Definition at line 138 of file Trajectory.hpp.