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

Store state information of a physics::Collision object. More...

#include <physics/phyiscs.hh>

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

Public Member Functions

 CollisionState ()
 Default constructor.
 
 CollisionState (const CollisionPtr _collision)
 Constructor.
 
virtual ~CollisionState ()
 Destructor.
 
math::Pose GetPose () const
 Get the Collision pose.
 
virtual void Load (sdf::ElementPtr _elem)
 Load state from SDF element.
 
- Public Member Functions inherited from gazebo::physics::State
 State ()
 Default constructor.
 
 State (const std::string &_name, const common::Time &_realTime, const common::Time &_simTime)
 Constructor.
 
virtual ~State ()
 Destructor.
 
std::string GetName () const
 Get the name associated with this State.
 
common::Time GetRealTime () const
 Get the real time when this state was generated.
 
common::Time GetSimTime () const
 Get the sim time when this state was generated.
 
common::Time GetWallTime () const
 Get the wall time when this state was generated.
 

Additional Inherited Members

- Protected Attributes inherited from gazebo::physics::State
std::string name
 Name associated with this State.
 
common::Time realTime
 
common::Time simTime
 
common::Time wallTime
 Times for the state data.
 

Detailed Description

Store state information of a physics::Collision object.

This class captures the entire state of a Collision at one specific time during a simulation run.

State of a Collision is its Pose.

Constructor & Destructor Documentation

gazebo::physics::CollisionState::CollisionState ( )

Default constructor.

gazebo::physics::CollisionState::CollisionState ( const CollisionPtr  _collision)

Constructor.

Build a CollisionState from an existing Collision.

Parameters
[in]_modelPointer to the Link from which to gather state info.
virtual gazebo::physics::CollisionState::~CollisionState ( )
virtual

Destructor.

Member Function Documentation

math::Pose gazebo::physics::CollisionState::GetPose ( ) const

Get the Collision pose.

virtual void gazebo::physics::CollisionState::Load ( sdf::ElementPtr  _elem)
virtual

Load state from SDF element.

Load CollisionState information from stored data in and SDF::Element

Parameters
[in]_elemPointer to the SDF::Element containing state info.

Implements gazebo::physics::State.


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