21 #ifndef _JOINTSTATE_HH_
22 #define _JOINTSTATE_HH_
60 public:
explicit JointState(
const sdf::ElementPtr _sdf);
74 public:
virtual void Load(
const sdf::ElementPtr _elem);
78 public:
unsigned int GetAngleCount()
const;
84 public:
math::Angle GetAngle(
unsigned int _axis)
const;
88 public:
const std::vector<math::Angle> &GetAngles()
const;
92 public:
bool IsZero()
const;
96 public:
void FillSDF(sdf::ElementPtr _sdf);
117 public:
inline friend std::ostream &
operator<<(std::ostream &_out,
120 _out <<
"<joint name='" << _state.
GetName() <<
"'>";
123 for (std::vector<math::Angle>::const_iterator iter =
124 _state.angles.begin(); iter != _state.angles.end(); ++iter)
126 _out <<
"<angle axis='" << i <<
"'>" << (*iter) <<
"</angle>";
134 private: std::vector<math::Angle> angles;
std::string GetName() const
Get the name associated with this State.
State of an entity.
Definition: State.hh:43
friend std::ostream & operator<<(std::ostream &_out, const gazebo::physics::JointState &_state)
Stream insertion operator.
Definition: JointState.hh:117
keeps track of state of a physics::Joint
Definition: JointState.hh:40
boost::shared_ptr< Joint > JointPtr
Definition: PhysicsTypes.hh:98
An angle and related functions.
Definition: Angle.hh:52
#define GAZEBO_VISIBLE
Use to represent "symbol visible" if supported.
Definition: system.hh:48
A Time class, can be used to hold wall- or sim-time.
Definition: Time.hh:43