21 #ifndef _LINKSTATE_HH_
22 #define _LINKSTATE_HH_
75 public:
explicit LinkState(
const sdf::ElementPtr _sdf);
94 public:
virtual void Load(
const sdf::ElementPtr _elem);
102 public:
const math::Pose &GetVelocity()
const;
106 public:
const math::Pose &GetAcceleration()
const;
116 public:
unsigned int GetCollisionStateCount()
const;
125 public:
CollisionState GetCollisionState(
unsigned int _index)
const;
135 const std::string &_collisionName)
const;
139 public:
const std::vector<CollisionState> &GetCollisionStates()
const;
143 public:
bool IsZero()
const;
147 public:
void FillSDF(sdf::ElementPtr _sdf);
152 public:
virtual void SetWallTime(
const common::Time &_time);
156 public:
virtual void SetRealTime(
const common::Time &_time);
160 public:
virtual void SetSimTime(
const common::Time &_time);
181 public:
inline friend std::ostream &
operator<<(std::ostream &_out,
185 _out << std::fixed <<std::setprecision(5)
186 <<
"<link name='" << _state.
name <<
"'>"
188 << _state.pose.
pos.
x <<
" "
189 << _state.pose.
pos.
y <<
" "
190 << _state.pose.
pos.
z <<
" "
198 _out << std::fixed <<std::setprecision(4)
200 << _state.velocity.
pos.
x <<
" "
201 << _state.velocity.
pos.
y <<
" "
202 << _state.velocity.
pos.
z <<
" "
236 private: std::vector<CollisionState> collisionStates;
Encapsulates a position and rotation in three space.
Definition: Pose.hh:40
The Vector3 class represents the generic vector containing 3 elements.
Definition: Vector3.hh:43
std::string name
Name associated with this State.
Definition: State.hh:114
double x
X location.
Definition: Vector3.hh:302
double z
Z location.
Definition: Vector3.hh:308
State of an entity.
Definition: State.hh:43
Vector3 pos
The position.
Definition: Pose.hh:243
Quaternion rot
The rotation.
Definition: Pose.hh:246
friend std::ostream & operator<<(std::ostream &_out, const gazebo::physics::LinkState &_state)
Stream insertion operator.
Definition: LinkState.hh:181
Store state information of a physics::Collision object.
Definition: CollisionState.hh:42
Store state information of a physics::Link object.
Definition: LinkState.hh:49
#define GAZEBO_VISIBLE
Use to represent "symbol visible" if supported.
Definition: system.hh:48
double y
Y location.
Definition: Vector3.hh:305
boost::shared_ptr< Link > LinkPtr
Definition: PhysicsTypes.hh:90
A Time class, can be used to hold wall- or sim-time.
Definition: Time.hh:43
Vector3 GetAsEuler() const
Return the rotation in Euler angles.