JointState.hh
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2012-2015 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 /* Desc: A joint state
18  * Author: Nate Koenig
19  */
20 
21 #ifndef _JOINTSTATE_HH_
22 #define _JOINTSTATE_HH_
23 
24 #ifdef _WIN32
25  // Ensure that Winsock2.h is included before Windows.h, which can get
26  // pulled in by anybody (e.g., Boost).
27  #include <Winsock2.h>
28 #endif
29 
30 #include <vector>
31 #include <string>
32 
33 #include "gazebo/physics/State.hh"
34 #include "gazebo/math/Pose.hh"
35 #include "gazebo/util/system.hh"
36 
37 namespace gazebo
38 {
39  namespace physics
40  {
43 
47  {
49  public: JointState();
50 
56  public: JointState(JointPtr _joint, const common::Time &_realTime,
57  const common::Time &_simTime, const uint64_t _iterations);
58 
61  public: explicit JointState(JointPtr _joint);
62 
67  public: explicit JointState(const sdf::ElementPtr _sdf);
68 
70  public: virtual ~JointState();
71 
76  public: void Load(JointPtr _joint, const common::Time &_realTime,
77  const common::Time &_simTime);
78 
81  public: virtual void Load(const sdf::ElementPtr _elem);
82 
85  public: unsigned int GetAngleCount() const;
86 
91  public: math::Angle GetAngle(unsigned int _axis) const;
92 
95  public: const std::vector<math::Angle> &GetAngles() const;
96 
99  public: bool IsZero() const;
100 
103  public: void FillSDF(sdf::ElementPtr _sdf);
104 
108  public: JointState &operator=(const JointState &_state);
109 
113  public: JointState operator-(const JointState &_state) const;
114 
118  public: JointState operator+(const JointState &_state) const;
119 
124  public: inline friend std::ostream &operator<<(std::ostream &_out,
125  const gazebo::physics::JointState &_state)
126  {
127  _out << "<joint name='" << _state.GetName() << "'>";
128 
129  int i = 0;
130  for (std::vector<math::Angle>::const_iterator iter =
131  _state.angles.begin(); iter != _state.angles.end(); ++iter)
132  {
133  _out << "<angle axis='" << i << "'>" << (*iter) << "</angle>";
134  }
135 
136  _out << "</joint>";
137 
138  return _out;
139  }
140 
141  private: std::vector<math::Angle> angles;
142  };
144  }
145 }
146 #endif
std::string GetName() const
Get the name associated with this State.
#define GZ_PHYSICS_VISIBLE
Definition: system.hh:318
State of an entity.
Definition: State.hh:49
friend std::ostream & operator<<(std::ostream &_out, const gazebo::physics::JointState &_state)
Stream insertion operator.
Definition: JointState.hh:124
keeps track of state of a physics::Joint
Definition: JointState.hh:46
boost::shared_ptr< Joint > JointPtr
Definition: PhysicsTypes.hh:100
An angle and related functions.
Definition: Angle.hh:53
A Time class, can be used to hold wall- or sim-time.
Definition: Time.hh:39