Ignition Gazebo

API Reference

6.9.0
Common.hh
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2019 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 IGNITION_GAZEBO_SYSTEMS_MULTICOPTERVELOCITYCONTROL_COMMON_HH_
19 #define IGNITION_GAZEBO_SYSTEMS_MULTICOPTERVELOCITYCONTROL_COMMON_HH_
20 
21 #include <Eigen/Geometry>
22 #include <optional>
23 #include <vector>
24 
25 #include <sdf/sdf.hh>
26 
27 #include "ignition/gazebo/config.hh"
29 #include "ignition/gazebo/Model.hh"
30 
31 #include "Parameters.hh"
32 
33 namespace ignition
34 {
35 namespace gazebo
36 {
37 // Inline bracket to help doxygen filtering.
38 inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE {
39 namespace systems
40 {
41 namespace multicopter_control
42 {
44  struct EigenTwist
45  {
46  Eigen::Vector3d linear;
47  Eigen::Vector3d angular;
48  };
49 
52  struct FrameData
53  {
54  // Even though this struct contains Eigen objects, None of them are
55  // fixed-size vectorizable, so there is no need to override the new operator
56  Eigen::Isometry3d pose;
57  Eigen::Vector3d linearVelocityWorld;
58  Eigen::Vector3d angularVelocityBody;
59  };
60 
67  const sdf::ElementPtr &_sdf,
68  const Model &_model,
69  const Entity &_comLink);
70 
75  std::optional<Eigen::Matrix4Xd> calculateAllocationMatrix(
76  const RotorConfiguration &_rotorConfiguration);
77 
83  const Entity &_link);
84 
89  std::optional<FrameData> getFrameData(const EntityComponentManager &_ecm,
90  const Entity &_link,
91  const NoiseParameters &_noise);
92 
97  inline Eigen::Matrix3d skewMatrixFromVector(const Eigen::Vector3d &_vector)
98  {
99  Eigen::Matrix3d skewMatrix;
100  skewMatrix << 0, -_vector.z(), _vector.y(), _vector.z(), 0, -_vector.x(),
101  -_vector.y(), _vector.x(), 0;
102  return skewMatrix;
103  }
104 
109  inline Eigen::Vector3d vectorFromSkewMatrix(
110  const Eigen::Matrix3d &_skewMatrix)
111  {
112  return Eigen::Vector3d(_skewMatrix(2, 1), _skewMatrix(0, 2),
113  _skewMatrix(1, 0));
114  }
115 
116 } // namespace multicopter_control
117 } // namespace systems
118 } // namespace IGNITION_GAZEBO_VERSION_NAMESPACE
119 } // namespace gazebo
120 } // namespace ignition
121 
122 #endif
This class provides wrappers around entities and components which are more convenient and straight-fo...
Definition: Model.hh:60
Eigen::Vector3d linear
Definition: Common.hh:46
Frame data of a link including its pose and linear velocity in world frame as well as its angular vel...
Definition: Common.hh:52
Eigen::Vector3d linearVelocityWorld
Definition: Common.hh:57
Eigen::Vector3d angularVelocityBody
Definition: Common.hh:58
The EntityComponentManager constructs, deletes, and returns components and entities. A component can be of any class which inherits from components::BaseComponent.
Definition: EntityComponentManager.hh:66
Eigen::Vector3d vectorFromSkewMatrix(const Eigen::Matrix3d &_skewMatrix)
Creates a vector from a skew symmetric matrix(so3). This is sometimes referred to as the vee map or i...
Definition: Common.hh:109
Eigen::Vector3d angular
Definition: Common.hh:47
RotorConfiguration loadRotorConfiguration(const EntityComponentManager &_ecm, const sdf::ElementPtr &_sdf, const Model &_model, const Entity &_comLink)
Loads rotor configuration from SDF.
std::optional< FrameData > getFrameData(const EntityComponentManager &_ecm, const Entity &_link, const NoiseParameters &_noise)
Retrieves the frame data of the given link and applies noise.
Eigen::Isometry3d pose
Definition: Common.hh:56
Eigen::Matrix3d skewMatrixFromVector(const Eigen::Vector3d &_vector)
Creates a skew symmetric matrix (so(3)) from a vector. This is sometimes referred to as the hat map...
Definition: Common.hh:97
Struct containing linear and angular velocities.
Definition: Common.hh:44
std::optional< Eigen::Matrix4Xd > calculateAllocationMatrix(const RotorConfiguration &_rotorConfiguration)
Create the matrix that maps rotor velocities to thrust and moments.
Noise parameters used when computing frame data. These are all assumed to be gaussian.
Definition: Parameters.hh:84
This library is part of the Ignition Robotics project.
uint64_t Entity
An Entity identifies a single object in simulation such as a model, link, or light. At its core, an Entity is just an identifier.
Definition: Entity.hh:59
void createFrameDataComponents(EntityComponentManager &_ecm, const Entity &_link)
Creates components necessary for obtaining the frame data of the given link.