Node animation. More...
#include <common/common.hh>
Public Member Functions | |
| NodeAnimation (const std::string &_name) | |
| constructor More... | |
| ~NodeAnimation () | |
| Destructor. It empties the key frames list. More... | |
| void | AddKeyFrame (const double _time, const math::Matrix4 &_trans) GAZEBO_DEPRECATED(6.0) |
| Adds a key frame at a specific time. More... | |
| void | AddKeyFrame (const double _time, const ignition::math::Matrix4d &_trans) |
| Adds a key frame at a specific time. More... | |
| void | AddKeyFrame (const double _time, const math::Pose &_pose) GAZEBO_DEPRECATED(6.0) |
| Adds a key frame at a specific time. More... | |
| void | AddKeyFrame (const double _time, const ignition::math::Pose3d &_pose) |
| Adds a key frame at a specific time. More... | |
| ignition::math::Matrix4d | FrameAt (double _time, bool _loop=true) const |
| Returns a frame transformation at a specific time if a node does not exist at that time (with tolerance of 1e-6 sec), the transformation is interpolated. More... | |
| math::Matrix4 | GetFrameAt (double _time, bool _loop=true) const GAZEBO_DEPRECATED(6.0) |
| Returns a frame transformation at a specific time if a node does not exist at that time (with tolerance of 1e-6 sec), the transformation is interpolated. More... | |
| unsigned int | GetFrameCount () const |
| Returns the number of key frames. More... | |
| void | GetKeyFrame (const unsigned int _i, double &_time, math::Matrix4 &_trans) const GAZEBO_DEPRECATED(6.0) |
| Finds a key frame using the index. More... | |
| void | GetKeyFrame (const unsigned int _i, double &_time, ignition::math::Matrix4d &_trans) const |
| Finds a key frame using the index. More... | |
| std::pair< double, math::Matrix4 > | GetKeyFrame (const unsigned int _i) const GAZEBO_DEPRECATED(6.0) |
| Returns a key frame using the index. More... | |
| double | GetLength () const |
| Returns the duration of the animations. More... | |
| std::string | GetName () const |
| Returns the name. More... | |
| double | GetTimeAtX (const double _x) const |
| Returns the time where a transformation's translational value along the X axis is equal to _x. More... | |
| std::pair< double, ignition::math::Matrix4d > | KeyFrame (const unsigned int _i) const |
| Returns a key frame using the index. More... | |
| void | Scale (const double _scale) |
| Scales each transformation in the key frames. More... | |
| void | SetName (const std::string &_name) |
| Changes the name of the animation. More... | |
Protected Attributes | |
| std::map< double, ignition::math::Matrix4d > | keyFrames |
| the dictionary of key frames, indexed by time More... | |
| double | length |
| the duration of the animations (time of last key frame) More... | |
| std::string | name |
| the name of the animation More... | |
Node animation.
| gazebo::common::NodeAnimation::NodeAnimation | ( | const std::string & | _name | ) |
constructor
| [in] | _name | the name of the node |
| gazebo::common::NodeAnimation::~NodeAnimation | ( | ) |
Destructor. It empties the key frames list.
| void gazebo::common::NodeAnimation::AddKeyFrame | ( | const double | _time, |
| const math::Matrix4 & | _trans | ||
| ) |
Adds a key frame at a specific time.
| [in] | _time | the time of the key frame |
| [in] | _trans | the transformation |
| void gazebo::common::NodeAnimation::AddKeyFrame | ( | const double | _time, |
| const ignition::math::Matrix4d & | _trans | ||
| ) |
Adds a key frame at a specific time.
| [in] | _time | the time of the key frame |
| [in] | _trans | the transformation |
| void gazebo::common::NodeAnimation::AddKeyFrame | ( | const double | _time, |
| const math::Pose & | _pose | ||
| ) |
Adds a key frame at a specific time.
| [in] | _time | the time of the key frame |
| [in] | _pose | the pose |
| void gazebo::common::NodeAnimation::AddKeyFrame | ( | const double | _time, |
| const ignition::math::Pose3d & | _pose | ||
| ) |
Adds a key frame at a specific time.
| [in] | _time | the time of the key frame |
| [in] | _pose | the pose |
| ignition::math::Matrix4d gazebo::common::NodeAnimation::FrameAt | ( | double | _time, |
| bool | _loop = true |
||
| ) | const |
Returns a frame transformation at a specific time if a node does not exist at that time (with tolerance of 1e-6 sec), the transformation is interpolated.
| [in] | _time | the time |
| [in] | _loop | when true, the time is divided by the duration (see GetLength) |
| math::Matrix4 gazebo::common::NodeAnimation::GetFrameAt | ( | double | _time, |
| bool | _loop = true |
||
| ) | const |
Returns a frame transformation at a specific time if a node does not exist at that time (with tolerance of 1e-6 sec), the transformation is interpolated.
| [in] | _time | the time |
| [in] | _loop | when true, the time is divided by the duration (see GetLength) |
| unsigned int gazebo::common::NodeAnimation::GetFrameCount | ( | ) | const |
Returns the number of key frames.
| void gazebo::common::NodeAnimation::GetKeyFrame | ( | const unsigned int | _i, |
| double & | _time, | ||
| math::Matrix4 & | _trans | ||
| ) | const |
Finds a key frame using the index.
Note the index of a key frame can change as frames are added.
| [in] | _i | the index |
| [out] | _time | the time of the frame, or -1 if the index id is out of bounds |
| [out] | _trans | the transformation for this key frame |
| void gazebo::common::NodeAnimation::GetKeyFrame | ( | const unsigned int | _i, |
| double & | _time, | ||
| ignition::math::Matrix4d & | _trans | ||
| ) | const |
Finds a key frame using the index.
Note the index of a key frame can change as frames are added.
| [in] | _i | the index |
| [out] | _time | the time of the frame, or -1 if the index id is out of bounds |
| [out] | _trans | the transformation for this key frame |
| std::pair<double, math::Matrix4> gazebo::common::NodeAnimation::GetKeyFrame | ( | const unsigned int | _i | ) | const |
Returns a key frame using the index.
Note the index of a key frame can change as frames are added.
| [in] | _i | the index |
| double gazebo::common::NodeAnimation::GetLength | ( | ) | const |
Returns the duration of the animations.
| std::string gazebo::common::NodeAnimation::GetName | ( | ) | const |
Returns the name.
| double gazebo::common::NodeAnimation::GetTimeAtX | ( | const double | _x | ) | const |
Returns the time where a transformation's translational value along the X axis is equal to _x.
When no transformation is found (within a tolerance of 1e-6), the time is interpolated.
| [in] | _x | the value along x. You must ensure that _x is within a valid range. |
| std::pair<double, ignition::math::Matrix4d> gazebo::common::NodeAnimation::KeyFrame | ( | const unsigned int | _i | ) | const |
Returns a key frame using the index.
Note the index of a key frame can change as frames are added.
| [in] | _i | the index |
| void gazebo::common::NodeAnimation::Scale | ( | const double | _scale | ) |
Scales each transformation in the key frames.
This only affects the translational values.
| [in] | _scale | the scaling factor |
| void gazebo::common::NodeAnimation::SetName | ( | const std::string & | _name | ) |
Changes the name of the animation.
| [in] | the | new name |
|
protected |
the dictionary of key frames, indexed by time
|
protected |
the duration of the animations (time of last key frame)
|
protected |
the name of the animation