17 #ifndef GAZEBO_PHYSICS_JOINTSTATE_HH_
18 #define GAZEBO_PHYSICS_JOINTSTATE_HH_
28 #include <ignition/math/Angle.hh>
53 const common::Time &_simTime,
const uint64_t _iterations);
63 public:
explicit JointState(
const sdf::ElementPtr _sdf);
77 public:
virtual void Load(
const sdf::ElementPtr _elem);
81 public:
unsigned int GetAngleCount()
const;
93 public:
double Position(
const unsigned int _axis = 0)
const;
101 public:
const std::vector<double> &Positions()
const;
105 public:
bool IsZero()
const;
109 public:
void FillSDF(sdf::ElementPtr _sdf);
130 public:
inline friend std::ostream &
operator<<(std::ostream &_out,
135 _out <<
"<joint name='" << _state.
GetName() <<
"'>";
138 for (std::vector<double>::const_iterator iter =
139 _state.positions.begin(); iter != _state.positions.end(); ++iter)
141 _out <<
"<angle axis='" << i <<
"'>" << (*iter) <<
"</angle>";
151 private: std::vector<double> positions;
std::string GetName() const
Get the name associated with this State.
boost::shared_ptr< Joint > JointPtr
Definition: PhysicsTypes.hh:117
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:130
keeps track of state of a physics::Joint
Definition: JointState.hh:42
unsigned int GetAngleCount() const
Get the number of angles.
A Time class, can be used to hold wall- or sim-time.
Definition: Time.hh:44