21 #ifndef _LINKSTATE_HH_ 22 #define _LINKSTATE_HH_ 64 const common::Time &_simTime,
const uint64_t _iterations);
77 public:
explicit LinkState(
const sdf::ElementPtr _sdf);
91 const common::Time &_simTime,
const uint64_t _iterations);
97 public:
virtual void Load(
const sdf::ElementPtr _elem);
105 public:
const math::Pose &GetVelocity()
const;
109 public:
const math::Pose &GetAcceleration()
const;
119 public:
unsigned int GetCollisionStateCount()
const;
128 public:
CollisionState GetCollisionState(
unsigned int _index)
const;
138 const std::string &_collisionName)
const;
142 public:
const std::vector<CollisionState> &GetCollisionStates()
const;
146 public:
bool IsZero()
const;
150 public:
void FillSDF(sdf::ElementPtr _sdf);
155 public:
virtual void SetWallTime(
const common::Time &_time);
159 public:
virtual void SetRealTime(
const common::Time &_time);
163 public:
virtual void SetSimTime(
const common::Time &_time);
168 public:
virtual void SetIterations(
const uint64_t _iterations);
189 public:
inline friend std::ostream &
operator<<(std::ostream &_out,
193 _out.unsetf(std::ios_base::floatfield);
194 _out << std::setprecision(4)
195 <<
"<link name='" << _state.
name <<
"'>" 209 _out.unsetf(std::ios_base::floatfield);
210 _out << std::setprecision(4)
239 public:
void SetRecordVelocity(
const bool _record);
243 public:
bool RecordVelocity()
const;
258 private: std::vector<CollisionState> collisionStates;
double x
X location.
Definition: Vector3.hh:311
Quaternion rot
The rotation.
Definition: Pose.hh:255
boost::shared_ptr< Link > LinkPtr
Definition: PhysicsTypes.hh:100
std::string name
Name associated with this State.
Definition: State.hh:130
double y
Y location.
Definition: Vector3.hh:314
bool RecordVelocity() const
Get whether link velocity is recorded.
Forward declarations for the common classes.
Definition: Animation.hh:33
Encapsulates a position and rotation in three space.
Definition: Pose.hh:37
The Vector3 class represents the generic vector containing 3 elements.
Definition: Vector3.hh:39
Vector3 GetAsEuler() const
Return the rotation in Euler angles.
State of an entity.
Definition: State.hh:49
double z
Z location.
Definition: Vector3.hh:317
Vector3 pos
The position.
Definition: Pose.hh:252
friend std::ostream & operator<<(std::ostream &_out, const gazebo::physics::LinkState &_state)
Stream insertion operator.
Definition: LinkState.hh:189
T precision(const T &_a, const unsigned int &_precision)
get value at a specified precision
Definition: Helpers.hh:182
Store state information of a physics::Collision object.
Definition: CollisionState.hh:42
Store state information of a physics::Link object.
Definition: LinkState.hh:50
A Time class, can be used to hold wall- or sim-time.
Definition: Time.hh:44