Store state information of a physics::Model object. More...
#include <physics/physics.hh>
Inherits State.
Public Member Functions | |
| ModelState () | |
| Default constructor.  More... | |
| ModelState (const ModelPtr _model, const common::Time &_realTime, const common::Time &_simTime, const uint64_t _iterations) | |
| Constructor.  More... | |
| ModelState (const ModelPtr _model) | |
| Constructor.  More... | |
| ModelState (const sdf::ElementPtr _sdf) | |
| Constructor.  More... | |
| virtual | ~ModelState () | 
| Destructor.  More... | |
| void | FillSDF (sdf::ElementPtr _sdf) | 
| Populate a state SDF element with data from the object.  More... | |
| uint64_t | GetIterations () const | 
| Get the iterations when this state was generated.  More... | |
| JointState | GetJointState (unsigned int _index) const | 
| Get a Joint state.  More... | |
| JointState | GetJointState (const std::string &_jointName) const | 
| Get a Joint state by Joint name.  More... | |
| unsigned int | GetJointStateCount () const | 
| Get the number of joint states.  More... | |
| JointState_M | GetJointStates (const boost::regex &_regex) const | 
| Get joint states based on a regular expression.  More... | |
| const JointState_M & | GetJointStates () const | 
| Get the joint states.  More... | |
| LinkState | GetLinkState (const std::string &_linkName) const | 
| Get a link state by Link name.  More... | |
| unsigned int | GetLinkStateCount () const | 
| Get the number of link states.  More... | |
| LinkState_M | GetLinkStates (const boost::regex &_regex) const | 
| Get link states based on a regular expression.  More... | |
| const LinkState_M & | GetLinkStates () const | 
| Get the link states.  More... | |
| std::string | GetName () const | 
| Get the name associated with this State.  More... | |
| const math::Pose & | GetPose () const | 
| Get the stored model pose.  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... | |
| bool | HasJointState (const std::string &_jointName) const | 
| Return true if there is a joint with the specified name.  More... | |
| bool | HasLinkState (const std::string &_linkName) const | 
| Return true if there is a link with the specified name.  More... | |
| bool | HasNestedModelState (const std::string &_modelName) const | 
| Return true if there is a nested model with the specified name.  More... | |
| bool | IsZero () const | 
| Return true if the values in the state are zero.  More... | |
| void | Load (const ModelPtr _model, const common::Time &_realTime, const common::Time &_simTime, const uint64_t _iterations) | 
| Load state from Model pointer.  More... | |
| virtual void | Load (const sdf::ElementPtr _elem) | 
| Load state from SDF element.  More... | |
| ModelState | NestedModelState (const std::string &_modelName) const | 
| Get a model state by model name.  More... | |
| unsigned int | NestedModelStateCount () const | 
| Get the number of model states.  More... | |
| const ModelState_M & | NestedModelStates () const | 
| Get the nested model states.  More... | |
| ModelState | operator+ (const ModelState &_state) const | 
| Addition operator.  More... | |
| State | operator- (const State &_state) const | 
| Subtraction operator.  More... | |
| ModelState | operator- (const ModelState &_state) const | 
| Subtraction operator.  More... | |
| ModelState & | operator= (const ModelState &_state) | 
| Assignment operator.  More... | |
| const ignition::math::Vector3d & | Scale () const | 
| Get the stored model scale.  More... | |
| virtual void | SetIterations (const uint64_t _iterations) | 
| Set the simulation iterations when this state was generated.  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 | |
| uint64_t | iterations | 
| The number of simulation iterations when this state was generated.  More... | |
| std::string | name | 
| Name associated with this State.  More... | |
| common::Time | realTime | 
| common::Time | simTime | 
| common::Time | wallTime | 
| Times for the state data.  More... | |
Friends | |
| std::ostream & | operator<< (std::ostream &_out, const gazebo::physics::ModelState &_state) | 
| Stream insertion operator.  More... | |
Store state information of a physics::Model object.
This class captures the entire state of a Model at one specific time during a simulation run.
State of a Model includes the state of all its child Links and Joints.
| ModelState | ( | ) | 
Default constructor.
| ModelState | ( | const ModelPtr | _model, | 
| const common::Time & | _realTime, | ||
| const common::Time & | _simTime, | ||
| const uint64_t | _iterations | ||
| ) | 
Constructor.
Build a ModelState from an existing Model.
| [in] | _model | Pointer to the model from which to gather state info. | 
| [in] | _realTime | Real time stamp. | 
| [in] | _simTime | Sim time stamp. | 
| [in] | _iterations | Simulation iterations. | 
      
  | 
  explicit | 
Constructor.
Build a ModelState from an existing Model.
| [in] | _model | Pointer to the model from which to gather state info. | 
      
  | 
  explicit | 
Constructor.
Build a ModelState from SDF data
| [in] | _sdf | SDF data to load a model state from. | 
      
  | 
  virtual | 
Destructor.
| void FillSDF | ( | sdf::ElementPtr | _sdf | ) | 
Populate a state SDF element with data from the object.
| [out] | _sdf | SDF element to populate. | 
      
  | 
  inherited | 
Get the iterations when this state was generated.
| JointState GetJointState | ( | unsigned int | _index | ) | const | 
Get a Joint state.
Return a JointState based on a index, where index is between 0...ModelState::GetJointStateCount().
| [in] | _index | Index of a JointState. | 
| common::Exception | When _index is out of range. | 
| JointState GetJointState | ( | const std::string & | _jointName | ) | const | 
Get a Joint state by Joint name.
Searches through all JointStates. Returns the JointState with the matching name, if any.
| [in] | _jointName | Name of the JointState. | 
| common::Exception | When _jointName is invalid. | 
| unsigned int GetJointStateCount | ( | ) | const | 
Get the number of joint states.
Returns the number of JointStates recorded.
| JointState_M GetJointStates | ( | const boost::regex & | _regex | ) | const | 
Get joint states based on a regular expression.
| [in] | _regex | The regular expression. | 
| const JointState_M& GetJointStates | ( | ) | const | 
Get the joint states.
| LinkState GetLinkState | ( | const std::string & | _linkName | ) | const | 
| unsigned int GetLinkStateCount | ( | ) | const | 
Get the number of link states.
This returns the number of Links recorded.
| LinkState_M GetLinkStates | ( | const boost::regex & | _regex | ) | const | 
Get link states based on a regular expression.
| [in] | _regex | The regular expression. | 
| const LinkState_M& GetLinkStates | ( | ) | const | 
Get the link states.
      
  | 
  inherited | 
| const math::Pose& GetPose | ( | ) | const | 
Get the stored model pose.
      
  | 
  inherited | 
Get the real time when this state was generated.
      
  | 
  inherited | 
Get the sim time when this state was generated.
      
  | 
  inherited | 
Get the wall time when this state was generated.
| bool HasJointState | ( | const std::string & | _jointName | ) | const | 
Return true if there is a joint with the specified name.
| [in] | _jointName | Name of the Jointtate. | 
| bool HasLinkState | ( | const std::string & | _linkName | ) | const | 
Return true if there is a link with the specified name.
| [in] | _linkName | Name of the LinkState. | 
| bool HasNestedModelState | ( | const std::string & | _modelName | ) | const | 
Return true if there is a nested model with the specified name.
| [in] | _modelName | Name of the model state. | 
| bool IsZero | ( | ) | const | 
Return true if the values in the state are zero.
| void Load | ( | const ModelPtr | _model, | 
| const common::Time & | _realTime, | ||
| const common::Time & | _simTime, | ||
| const uint64_t | _iterations | ||
| ) | 
Load state from Model pointer.
Build a ModelState from an existing Model.
| [in] | _model | Pointer to the model from which to gather state info. | 
| [in] | _realTime | Real time stamp. | 
| [in] | _simTime | Sim time stamp. | 
| [in] | _iterations | Simulation iterations. | 
      
  | 
  virtual | 
Load state from SDF element.
Load ModelState information from stored data in and SDF::Element
| [in] | _elem | Pointer to the SDF::Element containing state info. | 
Reimplemented from State.
| ModelState NestedModelState | ( | const std::string & | _modelName | ) | const | 
Get a model state by model name.
Searches through all nested model states. Returns the model state with the matching name, if any.
| [in] | _modelName | Name of the model state | 
| common::Exception | When _modelName is invalid. | 
| unsigned int NestedModelStateCount | ( | ) | const | 
Get the number of model states.
This returns the number of nested model states recorded.
| const ModelState_M& NestedModelStates | ( | ) | const | 
Get the nested model states.
| ModelState operator+ | ( | const ModelState & | _state | ) | const | 
Addition operator.
| [in] | _pt | A state to substract. | 
Subtraction operator.
| [in] | _pt | A state to substract. | 
| ModelState operator- | ( | const ModelState & | _state | ) | const | 
Subtraction operator.
| [in] | _pt | A state to substract. | 
| ModelState& operator= | ( | const ModelState & | _state | ) | 
| const ignition::math::Vector3d& Scale | ( | ) | const | 
Get the stored model scale.
      
  | 
  virtual | 
Set the simulation iterations when this state was generated.
| [in] | _iterations | Simulation iterations when the data was recorded. | 
Reimplemented from State.
      
  | 
  inherited | 
      
  | 
  virtual | 
Set the real time when this state was generated.
| [in] | _time | Clock time since simulation was stated. | 
Reimplemented from State.
      
  | 
  virtual | 
Set the sim time when this state was generated.
| [in] | _time | Simulation time when the data was recorded. | 
Reimplemented from State.
      
  | 
  virtual | 
      
  | 
  friend | 
Stream insertion operator.
| [in] | _out | output stream. | 
| [in] | _state | Model state to output. | 
      
  | 
  protectedinherited | 
The number of simulation iterations when this state was generated.
      
  | 
  protectedinherited | 
Name associated with this State.
      
  | 
  protectedinherited | 
      
  | 
  protectedinherited | 
      
  | 
  protectedinherited | 
Times for the state data.