17 #ifndef GAZEBO_PHYSICS_JOINTSTATE_HH_ 18 #define GAZEBO_PHYSICS_JOINTSTATE_HH_ 22 #include <ignition/math/Angle.hh> 47 const common::Time &_simTime,
const uint64_t _iterations);
57 public:
explicit JointState(
const sdf::ElementPtr _sdf);
71 public:
virtual void Load(
const sdf::ElementPtr _elem);
75 public:
unsigned int GetAngleCount()
const;
87 public:
double Position(
const unsigned int _axis = 0)
const;
95 public:
const std::vector<double> &Positions()
const;
99 public:
bool IsZero()
const;
103 public:
void FillSDF(sdf::ElementPtr _sdf);
124 public:
inline friend std::ostream &
operator<<(std::ostream &_out,
129 _out <<
"<joint name='" << _state.
GetName() <<
"'>";
132 for (std::vector<double>::const_iterator iter =
133 _state.positions.begin(); iter != _state.positions.end(); ++iter)
135 _out <<
"<angle axis='" << i <<
"'>" << (*iter) <<
"</angle>";
145 private: std::vector<double> positions;
Forward declarations for the common classes.
Definition: Animation.hh:26
boost::shared_ptr< Joint > JointPtr
Definition: PhysicsTypes.hh:118
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:124
std::string GetName() const
Get the name associated with this State.
unsigned int GetAngleCount() const
Get the number of angles.
keeps track of state of a physics::Joint
Definition: JointState.hh:36
A Time class, can be used to hold wall- or sim-time.
Definition: Time.hh:47