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);
77 public:
virtual void Load(
const sdf::ElementPtr _elem);
93 public:
double Position(
const unsigned int _axis = 0)
const;
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;
A Time class, can be used to hold wall- or sim-time.
Definition: Time.hh:48
keeps track of state of a physics::Joint
Definition: JointState.hh:43
JointState(JointPtr _joint)
Constructor.
virtual ~JointState()
Destructor.
unsigned int GetAngleCount() const
Get the number of angles.
JointState operator+(const JointState &_state) const
Addition operator.
friend std::ostream & operator<<(std::ostream &_out, const gazebo::physics::JointState &_state)
Stream insertion operator.
Definition: JointState.hh:130
bool IsZero() const
Return true if the values in the state are zero.
JointState()
Default constructor.
JointState & operator=(const JointState &_state)
Assignment operator.
double Position(const unsigned int _axis=0) const
Get the joint position.
JointState operator-(const JointState &_state) const
Subtraction operator.
void Load(JointPtr _joint, const common::Time &_realTime, const common::Time &_simTime)
Load.
const std::vector< double > & Positions() const
Get the joint positions.
void FillSDF(sdf::ElementPtr _sdf)
Populate a state SDF element with data from the object.
virtual void Load(const sdf::ElementPtr _elem)
Load state from SDF element.
JointState(const sdf::ElementPtr _sdf)
Constructor.
JointState(JointPtr _joint, const common::Time &_realTime, const common::Time &_simTime, const uint64_t _iterations)
Constructor.
State of an entity.
Definition: State.hh:50
std::string GetName() const
Get the name associated with this State.
boost::shared_ptr< Joint > JointPtr
Definition: PhysicsTypes.hh:117
Forward declarations for the common classes.
Definition: Animation.hh:27