Public Member Functions | Protected Attributes | List of all members
gazebo::common::NodeAnimation Class Reference

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::Matrix4GetKeyFrame (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...
 

Detailed Description

Node animation.

Constructor & Destructor Documentation

gazebo::common::NodeAnimation::NodeAnimation ( const std::string &  _name)

constructor

Parameters
[in]_namethe name of the node
gazebo::common::NodeAnimation::~NodeAnimation ( )

Destructor. It empties the key frames list.

Member Function Documentation

void gazebo::common::NodeAnimation::AddKeyFrame ( const double  _time,
const math::Matrix4 _trans 
)

Adds a key frame at a specific time.

Parameters
[in]_timethe time of the key frame
[in]_transthe transformation
Deprecated:
See AddKeyFrame function accepts ignition::math::Matrix4d.
void gazebo::common::NodeAnimation::AddKeyFrame ( const double  _time,
const ignition::math::Matrix4d &  _trans 
)

Adds a key frame at a specific time.

Parameters
[in]_timethe time of the key frame
[in]_transthe transformation
void gazebo::common::NodeAnimation::AddKeyFrame ( const double  _time,
const math::Pose _pose 
)

Adds a key frame at a specific time.

Parameters
[in]_timethe time of the key frame
[in]_posethe pose
Deprecated:
See AddKeyFrame function that accepts ignition::math::Pose3d
void gazebo::common::NodeAnimation::AddKeyFrame ( const double  _time,
const ignition::math::Pose3d &  _pose 
)

Adds a key frame at a specific time.

Parameters
[in]_timethe time of the key frame
[in]_posethe 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.

Parameters
[in]_timethe time
[in]_loopwhen 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.

Parameters
[in]_timethe time
[in]_loopwhen true, the time is divided by the duration (see GetLength)
Deprecated:
See FrameAt function that return ignition::math::Matrix4d.
unsigned int gazebo::common::NodeAnimation::GetFrameCount ( ) const

Returns the number of key frames.

Returns
the count
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.

Parameters
[in]_ithe index
[out]_timethe time of the frame, or -1 if the index id is out of bounds
[out]_transthe transformation for this key frame
Deprecated:
See GetKeyFrame function that accepts ignition::math::Matrix4d.
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.

Parameters
[in]_ithe index
[out]_timethe time of the frame, or -1 if the index id is out of bounds
[out]_transthe 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.

Parameters
[in]_ithe index
Returns
a pair that contains the time and transformation. Time is -1 if the index is out of bounds
Deprecated:
See KeyFrame function that return ignition::math::Matrix4d.
double gazebo::common::NodeAnimation::GetLength ( ) const

Returns the duration of the animations.

Returns
the time of the last animation
std::string gazebo::common::NodeAnimation::GetName ( ) const

Returns the name.

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.

Parameters
[in]_xthe 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.

Parameters
[in]_ithe index
Returns
a pair that contains the time and transformation. Time is -1 if the index is out of bounds
void gazebo::common::NodeAnimation::Scale ( const double  _scale)

Scales each transformation in the key frames.

This only affects the translational values.

Parameters
[in]_scalethe scaling factor
void gazebo::common::NodeAnimation::SetName ( const std::string &  _name)

Changes the name of the animation.

Parameters
[in]thenew name

Member Data Documentation

std::map<double, ignition::math::Matrix4d> gazebo::common::NodeAnimation::keyFrames
protected

the dictionary of key frames, indexed by time

double gazebo::common::NodeAnimation::length
protected

the duration of the animations (time of last key frame)

std::string gazebo::common::NodeAnimation::name
protected

the name of the animation


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