LinkState.hh
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2012 Open Source Robotics Foundation
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9  *
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  *
16 */
17 #ifndef GAZEBO_PHYSICS_LINKSTATE_HH_
18 #define GAZEBO_PHYSICS_LINKSTATE_HH_
19 
20 #include <iostream>
21 #include <vector>
22 #include <string>
23 
24 #include <ignition/math/Pose3.hh>
25 #include <sdf/sdf.hh>
26 
27 #include "gazebo/physics/State.hh"
29 #include "gazebo/math/Pose.hh"
30 #include "gazebo/util/system.hh"
31 
32 namespace gazebo
33 {
34  namespace physics
35  {
38 
47  class GZ_PHYSICS_VISIBLE LinkState : public State
48  {
50  public: LinkState();
51 
60  public: LinkState(const LinkPtr _link, const common::Time &_realTime,
61  const common::Time &_simTime, const uint64_t _iterations);
62 
68  public: explicit LinkState(const LinkPtr _link);
69 
74  public: explicit LinkState(const sdf::ElementPtr _sdf);
75 
77  public: virtual ~LinkState();
78 
87  public: void Load(const LinkPtr _link, const common::Time &_realTime,
88  const common::Time &_simTime, const uint64_t _iterations);
89 
94  public: virtual void Load(const sdf::ElementPtr _elem);
95 
99  public: const math::Pose GetPose() const GAZEBO_DEPRECATED(8.0);
100 
103  public: const ignition::math::Pose3d &Pose() const;
104 
108  public: const math::Pose GetVelocity() const GAZEBO_DEPRECATED(8.0);
109 
112  public: const ignition::math::Pose3d &Velocity() const;
113 
117  public: const math::Pose GetAcceleration() const GAZEBO_DEPRECATED(8.0);
118 
121  public: const ignition::math::Pose3d &Acceleration() const;
122 
126  public: const math::Pose GetWrench() const GAZEBO_DEPRECATED(8.0);
127 
130  public: const ignition::math::Pose3d &Wrench() const;
131 
136  public: unsigned int GetCollisionStateCount() const;
137 
145  public: CollisionState GetCollisionState(unsigned int _index) const;
146 
154  public: CollisionState GetCollisionState(
155  const std::string &_collisionName) const;
156 
159  public: const std::vector<CollisionState> &GetCollisionStates() const;
160 
163  public: bool IsZero() const;
164 
167  public: void FillSDF(sdf::ElementPtr _sdf);
168 
172  public: virtual void SetWallTime(const common::Time &_time);
173 
176  public: virtual void SetRealTime(const common::Time &_time);
177 
180  public: virtual void SetSimTime(const common::Time &_time);
181 
185  public: virtual void SetIterations(const uint64_t _iterations);
186 
190  public: LinkState &operator=(const LinkState &_state);
191 
195  public: LinkState operator-(const LinkState &_state) const;
196 
200  public: LinkState operator+(const LinkState &_state) const;
201 
206  public: inline friend std::ostream &operator<<(std::ostream &_out,
207  const gazebo::physics::LinkState &_state)
208  {
209  ignition::math::Vector3d euler(_state.pose.Rot().Euler());
210  _out.unsetf(std::ios_base::floatfield);
211  _out << std::setprecision(4)
212  << "<link name='" << _state.name << "'>"
213  << "<pose>"
214  << ignition::math::precision(_state.pose.Pos().X(), 4) << " "
215  << ignition::math::precision(_state.pose.Pos().Y(), 4) << " "
216  << ignition::math::precision(_state.pose.Pos().Z(), 4) << " "
217  << ignition::math::precision(euler.X(), 4) << " "
218  << ignition::math::precision(euler.Y(), 4) << " "
219  << ignition::math::precision(euler.Z(), 4) << " "
220  << "</pose>";
221 
222  if (_state.RecordVelocity())
223  {
225  euler = _state.velocity.Rot().Euler();
226  _out.unsetf(std::ios_base::floatfield);
227  _out << std::setprecision(4)
228  << "<velocity>"
229  << ignition::math::precision(_state.velocity.Pos().X(), 4) << " "
230  << ignition::math::precision(_state.velocity.Pos().Y(), 4) << " "
231  << ignition::math::precision(_state.velocity.Pos().Z(), 4) << " "
232  << ignition::math::precision(euler.X(), 4) << " "
233  << ignition::math::precision(euler.Y(), 4) << " "
234  << ignition::math::precision(euler.Z(), 4) << " "
235  << "</velocity>";
236  }
237  // << "<acceleration>" << _state.acceleration << "</acceleration>"
238  // << "<wrench>" << _state.wrench << "</wrench>";
239 
241  // for (std::vector<CollisionState>::const_iterator iter =
242  // _state.collisionStates.begin();
243  // iter != _state.collisionStates.end(); ++iter)
244  // {
245  // _out << *iter;
246  // }
247 
248  _out << "</link>";
249 
250  return _out;
251  }
252 
256  public: void SetRecordVelocity(const bool _record);
257 
260  public: bool RecordVelocity() const;
261 
263  private: ignition::math::Pose3d pose;
264 
266  private: ignition::math::Pose3d velocity;
267 
269  private: ignition::math::Pose3d acceleration;
270 
272  private: ignition::math::Pose3d wrench;
273 
275  private: std::vector<CollisionState> collisionStates;
276  };
278  }
279 }
280 #endif
boost::shared_ptr< Link > LinkPtr
Definition: PhysicsTypes.hh:109
std::string name
Name associated with this State.
Definition: State.hh:130
Encapsulates a position and rotation in three space.
Definition: Pose.hh:42
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:206
#define GAZEBO_DEPRECATED(version)
Definition: system.hh:302
Store state information of a physics::Collision object.
Definition: CollisionState.hh:44
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