21 #ifndef _JOINTSTATE_HH_    22 #define _JOINTSTATE_HH_    57                   const common::Time &_simTime, 
const uint64_t _iterations);
    67       public: 
explicit JointState(
const sdf::ElementPtr _sdf);
    81       public: 
virtual void Load(
const sdf::ElementPtr _elem);
    85       public: 
unsigned int GetAngleCount() 
const;
    91       public: 
math::Angle GetAngle(
unsigned int _axis) 
const;
    95       public: 
const std::vector<math::Angle> &GetAngles() 
const;
    99       public: 
bool IsZero() 
const;
   103       public: 
void FillSDF(sdf::ElementPtr _sdf);
   124       public: 
inline friend std::ostream &
operator<<(std::ostream &_out,
   127         _out << 
"<joint name='" << _state.
GetName() << 
"'>";
   130         for (std::vector<math::Angle>::const_iterator iter =
   131             _state.angles.begin(); iter != _state.angles.end(); ++iter)
   133           _out << 
"<angle axis='" << i << 
"'>" << (*iter) << 
"</angle>";
   141       private: std::vector<math::Angle> angles;
 Forward declarations for the common classes. 
Definition: Animation.hh:33
 
boost::shared_ptr< Joint > JointPtr
Definition: PhysicsTypes.hh:108
 
State of an entity. 
Definition: State.hh:49
 
friend std::ostream & operator<<(std::ostream &_out, const gazebo::physics::JointState &_state)
Stream insertion operator. 
Definition: JointState.hh:124
 
std::string GetName() const
Get the name associated with this State. 
 
keeps track of state of a physics::Joint 
Definition: JointState.hh:46
 
An angle and related functions. 
Definition: Angle.hh:53
 
A Time class, can be used to hold wall- or sim-time. 
Definition: Time.hh:44