All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Macros Groups Pages
Public Member Functions | Protected Attributes | List of all members
gazebo::physics::State Class Reference

State of an entity. More...

#include <physics/physics.hh>

Inheritance diagram for gazebo::physics::State:
Inheritance graph
[legend]

Public Member Functions

 State ()
 Default constructor. More...
 
 State (const std::string &_name, const common::Time &_realTime, const common::Time &_simTime)
 Constructor. More...
 
virtual ~State ()
 Destructor. More...
 
std::string GetName () const
 Get the name associated with this State. More...
 
common::Time GetRealTime () const
 Get the real time when this state was generated. More...
 
common::Time GetSimTime () const
 Get the sim time when this state was generated. More...
 
common::Time GetWallTime () const
 Get the wall time when this state was generated. More...
 
virtual void Load (const sdf::ElementPtr _elem)
 Load state from SDF element. More...
 
State operator- (const State &_state) const
 Subtraction operator. More...
 
Stateoperator= (const State &_state)
 Assignment operator. More...
 
void SetName (const std::string &_name)
 Set the name associated with this State. More...
 
virtual void SetRealTime (const common::Time &_time)
 Set the real time when this state was generated. More...
 
virtual void SetSimTime (const common::Time &_time)
 Set the sim time when this state was generated. More...
 
virtual void SetWallTime (const common::Time &_time)
 Set the wall time when this state was generated. More...
 

Protected Attributes

std::string name
 Name associated with this State. More...
 
common::Time realTime
 
common::Time simTime
 
common::Time wallTime
 Times for the state data. More...
 

Detailed Description

State of an entity.

This is the base class for all State information.

Constructor & Destructor Documentation

gazebo::physics::State::State ( )

Default constructor.

gazebo::physics::State::State ( const std::string &  _name,
const common::Time _realTime,
const common::Time _simTime 
)

Constructor.

Construct a State object using some basic information.

Parameters
_nameName associated with the State information. This is typically the name of an Entity. _realTime Clock time since simulation started.
_simTimeSimulation time associated with this State info.
virtual gazebo::physics::State::~State ( )
virtual

Destructor.

Member Function Documentation

std::string gazebo::physics::State::GetName ( ) const

Get the name associated with this State.

Returns
Name associated with this state information. Typically a name of an Entity.
common::Time gazebo::physics::State::GetRealTime ( ) const

Get the real time when this state was generated.

Returns
Clock time since simulation was stated.
common::Time gazebo::physics::State::GetSimTime ( ) const

Get the sim time when this state was generated.

Returns
Simulation time when the data was recorded.
common::Time gazebo::physics::State::GetWallTime ( ) const

Get the wall time when this state was generated.

Returns
The absolute clock time when the State data was recorded.
virtual void gazebo::physics::State::Load ( const sdf::ElementPtr  _elem)
virtual

Load state from SDF element.

Populates the State information from data stored in an SDF::Element

Parameters
_elemPointer to the SDF::Element

Reimplemented in gazebo::physics::ModelState, gazebo::physics::LinkState, gazebo::physics::WorldState, gazebo::physics::JointState, and gazebo::physics::CollisionState.

State gazebo::physics::State::operator- ( const State _state) const

Subtraction operator.

Parameters
[in]_ptA state to substract.
Returns
The resulting state.
State& gazebo::physics::State::operator= ( const State _state)

Assignment operator.

Parameters
[in]_stateState value
Returns
this
void gazebo::physics::State::SetName ( const std::string &  _name)

Set the name associated with this State.

Parameters
[in]_nameName associated with this state information. Typically the name of an Entity.
virtual void gazebo::physics::State::SetRealTime ( const common::Time _time)
virtual

Set the real time when this state was generated.

Parameters
[in]_timeClock time since simulation was stated.

Reimplemented in gazebo::physics::ModelState, gazebo::physics::LinkState, and gazebo::physics::WorldState.

virtual void gazebo::physics::State::SetSimTime ( const common::Time _time)
virtual

Set the sim time when this state was generated.

Parameters
[in]_timeSimulation time when the data was recorded.

Reimplemented in gazebo::physics::ModelState, gazebo::physics::LinkState, and gazebo::physics::WorldState.

virtual void gazebo::physics::State::SetWallTime ( const common::Time _time)
virtual

Set the wall time when this state was generated.

Parameters
[in]_timeThe absolute clock time when the State data was recorded.

Reimplemented in gazebo::physics::ModelState, gazebo::physics::LinkState, and gazebo::physics::WorldState.

Member Data Documentation

std::string gazebo::physics::State::name
protected

Name associated with this State.

common::Time gazebo::physics::State::realTime
protected
common::Time gazebo::physics::State::simTime
protected
common::Time gazebo::physics::State::wallTime
protected

Times for the state data.


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