Gazebo Physics

API Reference

5.3.2
gz/physics/RelativeQuantity.hh
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2017 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 
18 #ifndef GZ_PHYSICS_RELATIVEQUANTITY_HH_
19 #define GZ_PHYSICS_RELATIVEQUANTITY_HH_
20 
21 #include <gz/physics/FrameID.hh>
22 #include <gz/physics/FrameData.hh>
23 
24 namespace ignition
25 {
26  namespace physics
27  {
47  template <typename Q, std::size_t Dim, typename CoordinateSpace>
49  {
52  public: template <typename... Args>
53  explicit RelativeQuantity(const FrameID &_parentID, Args&&... _args);
54 
56  public: RelativeQuantity(const Q &_rawValue);
57 
74  public: Q &RelativeToParent();
75 
77  public: const Q &RelativeToParent() const;
78 
95  public: const FrameID &ParentFrame() const;
96 
99  public: void MoveToNewParentFrame(const FrameID &_newParentFrame);
100 
102  public: using Quantity = Q;
103 
106  public: using Space = CoordinateSpace;
107 
110  public: enum { Dimension = Dim };
111 
114  private: FrameID parentFrame;
115 
117  private: Q value;
118  };
119 
120  template <typename Q, std::size_t Dim, typename CoordinateSpace>
122  std::ostream& stream,
124  {
125  stream << "Parent Frame ID: " << _fq.ParentFrame().ID()
126  << "\nRelative To Parent:\n" << _fq.RelativeToParent();
127 
128  return stream;
129  }
130 
131  namespace detail
132  {
134  // Forward delcarations of CoordinateSpaces
135  template <typename, std::size_t> struct SESpace;
136  template <typename, std::size_t, typename> struct SOSpace;
137  template <typename, std::size_t> struct EuclideanSpace;
138  template <typename, std::size_t> struct LinearVelocitySpace;
139  template <typename, std::size_t> struct AngularVelocitySpace;
140  template <typename, std::size_t> struct LinearAccelerationSpace;
141  template <typename, std::size_t> struct AngularAccelerationSpace;
142  template <typename, std::size_t> struct VectorSpace;
143  template <typename, std::size_t> struct FrameSpace;
144  template <typename, std::size_t> struct AABBSpace;
145  template <typename, std::size_t> struct WrenchSpace;
146  // TODO(MXG): We can add more spaces to support other types like Moments
147  // of Inertia, Jacobians, Spatial Velocities/Accelerations, Wrench+Point
148  // pairs, and so on.
149  //
150  // Users can also define Spaces for their own types (see the header
151  // gz/physics/detail/FrameSemantics.hpp for example implementations)
152  // and use them seamlessly in the Frame Semantics infrastructure.
153  }
154 
156  template <typename Scalar, std::size_t Dim>
157  using RelativePose = RelativeQuantity<
158  Pose<Scalar, Dim>, Dim, detail::SESpace<Scalar, Dim>>;
160 
161 
162  template <typename Scalar, std::size_t Dim>
164  Eigen::Matrix<Scalar, Dim, Dim>, Dim,
165  detail::SOSpace<Scalar, Dim, Eigen::Matrix<Scalar, Dim, Dim>>>;
167 
168 
169  template <typename Scalar>
170  using RelativeQuaternion = RelativeQuantity<
171  Eigen::Quaternion<Scalar>, 3, detail::SOSpace<Scalar, 3,
172  Eigen::Quaternion<Scalar>>>;
173  // Note: Eigen only supports quaternions for 3 dimensional space, so we do
174  // not have a dimensionality template argument.
175  using RelativeQuaterniond = RelativeQuaternion<double>;
176  using RelativeQuaternionf = RelativeQuaternion<float>;
177 
179  template <typename Scalar, std::size_t Dim>
181  LinearVector<Scalar, Dim>, Dim, detail::EuclideanSpace<Scalar, Dim>>;
183 
184 
185  template <typename Scalar, std::size_t Dim>
187  LinearVector<Scalar, Dim>, Dim, detail::VectorSpace<Scalar, Dim>>;
189 
190 
191  template <typename Scalar, std::size_t Dim>
194  detail::VectorSpace<Scalar, (Dim*(Dim-1))/2>>;
196 
197 
198  template <typename Scalar, std::size_t Dim>
200  AlignedBox<Scalar, Dim>, Dim, detail::AABBSpace<Scalar, Dim>>;
202 
203 
204  template <typename Scalar, std::size_t Dim>
206  FrameData<Scalar, Dim>, Dim, detail::FrameSpace<Scalar, Dim>>;
208 
209 
210  template <typename Scalar, std::size_t Dim>
212  Wrench<Scalar, Dim>, Dim, detail::WrenchSpace<Scalar, Dim>>;
214  }
215 }
216 
217 #include <gz/physics/detail/RelativeQuantity.hh>
218 
219 #endif
RelativeQuaternion< float > RelativeQuaternionf
Definition: gz/physics/RelativeQuantity.hh:176
Eigen::AlignedBox< Scalar, Dim > AlignedBox
Definition: gz/physics/Geometry.hh:68
@ Dimension
Definition: gz/physics/RelativeQuantity.hh:110
RelativeQuantity(const FrameID &_parentID, Args &&... _args)
This constructor will specify the parent frame and then forward the remaining arguments to the constr...
Container for specifying Frame IDs. We do not want to use a generic integer type for this,...
Definition: gz/physics/FrameID.hh:46
Q Quantity
The underlying type of the quantity that is being expressed.
Definition: gz/physics/RelativeQuantity.hh:102
const FrameID & ParentFrame() const
Get the ID of this RelativeQuantity's parent frame.
void MoveToNewParentFrame(const FrameID &_newParentFrame)
This function will change the parent frame of your RelativeQuantity.
STL class.
std::size_t Dim std::ostream & operator<<(std::ostream &stream, const FrameData< Scalar, Dim > &_frame)
Definition: gz/physics/FrameData.hh:74
std::size_t ID() const
The numerical value of this FrameID's ID number.
Vector< Scalar, Dim > LinearVector
Definition: gz/physics/Geometry.hh:52
RelativeQuaternion< double > RelativeQuaterniond
Definition: gz/physics/RelativeQuantity.hh:175
Q & RelativeToParent()
Get the value of this RelativeQuantity relative to its parent frame. To get the value of this Relativ...
Eigen::Transform< Scalar, Dim, Eigen::Isometry > Pose
This is used by ignition-physics to represent rigid body transforms in 2D or 3D simulations....
Definition: gz/physics/Geometry.hh:44
The FrameData struct fully describes the kinematic state of a Frame with "Dim" dimensions and "Scalar...
Definition: gz/physics/FrameData.hh:42
IGN_PHYSICS_MAKE_ALL_TYPE_COMBOS(FrameData) template< typename Scalar
Definition: gz/physics/Geometry.hh:60
The RelativeQuantity class is a wrapper for classes that represent mathematical quantities (e....
Definition: gz/physics/RelativeQuantity.hh:48
RelativeQuantity< Pose< Scalar, Dim >, Dim, detail::SESpace< Scalar, Dim > > RelativePose
Definition: gz/physics/RelativeQuantity.hh:158
Vector< Scalar,(Dim *(Dim-1))/2 > AngularVector
Definition: gz/physics/Geometry.hh:56
CoordinateSpace Space
The mathematical space which defines how this quantity is transformed between reference frames.
Definition: gz/physics/RelativeQuantity.hh:106