17 #ifndef GAZEBO_PHYSICS_LINKSTATE_HH_
18 #define GAZEBO_PHYSICS_LINKSTATE_HH_
25 #include <ignition/math/Pose3.hh>
61 const common::Time &_simTime,
const uint64_t _iterations);
74 public:
explicit LinkState(
const sdf::ElementPtr _sdf);
88 const common::Time &_simTime,
const uint64_t _iterations);
94 public:
virtual void Load(
const sdf::ElementPtr _elem);
98 public:
const ignition::math::Pose3d &Pose()
const;
102 public:
const ignition::math::Pose3d &Velocity()
const;
106 public:
const ignition::math::Pose3d &Acceleration()
const;
110 public:
const ignition::math::Pose3d &Wrench()
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);
165 public:
virtual void SetIterations(
const uint64_t _iterations);
186 public:
inline friend std::ostream &
operator<<(std::ostream &_out,
189 ignition::math::Vector3d euler(_state.pose.Rot().Euler());
190 _out.unsetf(std::ios_base::floatfield);
191 _out << std::setprecision(4)
192 <<
"<link name='" << _state.
name <<
"'>"
194 << ignition::math::precision(_state.pose.Pos().X(), 4) <<
" "
195 << ignition::math::precision(_state.pose.Pos().Y(), 4) <<
" "
196 << ignition::math::precision(_state.pose.Pos().Z(), 4) <<
" "
197 << ignition::math::precision(euler.X(), 4) <<
" "
198 << ignition::math::precision(euler.Y(), 4) <<
" "
199 << ignition::math::precision(euler.Z(), 4) <<
" "
205 euler = _state.velocity.Rot().Euler();
206 _out.unsetf(std::ios_base::floatfield);
207 _out << std::setprecision(4)
209 << ignition::math::precision(_state.velocity.Pos().X(), 4) <<
" "
210 << ignition::math::precision(_state.velocity.Pos().Y(), 4) <<
" "
211 << ignition::math::precision(_state.velocity.Pos().Z(), 4) <<
" "
212 << ignition::math::precision(euler.X(), 4) <<
" "
213 << ignition::math::precision(euler.Y(), 4) <<
" "
214 << ignition::math::precision(euler.Z(), 4) <<
" "
236 public:
void SetRecordVelocity(
const bool _record);
240 public:
bool RecordVelocity()
const;
243 private: ignition::math::Pose3d pose;
247 private: ignition::math::Pose3d velocity;
251 private: ignition::math::Pose3d acceleration;
255 private: ignition::math::Pose3d wrench;
258 private: std::vector<CollisionState> collisionStates;
boost::shared_ptr< Link > LinkPtr
Definition: PhysicsTypes.hh:109
std::string name
Name associated with this State.
Definition: State.hh:130
State of an entity.
Definition: State.hh:49
friend std::ostream & operator<<(std::ostream &_out, const gazebo::physics::LinkState &_state)
Stream insertion operator.
Definition: LinkState.hh:186
Store state information of a physics::Collision object.
Definition: CollisionState.hh:43
bool RecordVelocity() const
Get whether link velocity is recorded.
Store state information of a physics::Link object.
Definition: LinkState.hh:47
A Time class, can be used to hold wall- or sim-time.
Definition: Time.hh:44