usv_gazebo_dynamics_plugin.hh
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2017 Brian Bingham
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 USV_GAZEBO_PLUGINS_DYNAMICS_PLUGIN_HH_
19 #define USV_GAZEBO_PLUGINS_DYNAMICS_PLUGIN_HH_
20 
21 #include <Eigen/Core>
22 #include <string>
23 #include <vector>
24 
25 #include <gazebo/common/common.hh>
26 #include <ignition/math/Vector3.hh>
27 #include <gazebo/physics/physics.hh>
28 #include <sdf/sdf.hh>
29 
33 
34 namespace gazebo
35 {
61  class UsvDynamicsPlugin : public ModelPlugin
62  {
64  public: UsvDynamicsPlugin();
65 
67  public: virtual ~UsvDynamicsPlugin() = default;
68 
69  // Documentation inherited.
70  public: virtual void Load(physics::ModelPtr _model,
71  sdf::ElementPtr _sdf);
72 
74  protected: virtual void Update();
75 
82  private: double SdfParamDouble(sdf::ElementPtr _sdfPtr,
83  const std::string &_paramName,
84  const double _defaultVal) const;
85 
90  private: double CircleSegment(double R, double h);
91 
93  private: physics::WorldPtr world;
94 
98  private: physics::LinkPtr link;
99 
101  private: common::Time prevUpdateTime;
102 
105  private: ignition::math::Vector3d prevLinVel;
106 
109  private: ignition::math::Vector3d prevAngVel;
110 
113  private: double paramXdotU;
114 
116  private: double paramYdotV;
117 
119  private: double paramNdotR;
120 
122  private: double paramXu;
123 
125  private: double paramXuu;
126 
128  private: double paramYv;
129 
131  private: double paramYvv;
132 
134  private: double paramZw;
135 
137  private: double paramKp;
138 
140  private: double paramMq;
141 
143  private: double paramNr;
144 
146  private: double paramNrr;
147 
149  private: double waterLevel;
150 
152  private: double waterDensity;
153 
155  private: double paramBoatLength;
156 
158  private: double paramBoatWidth;
159 
161  private: double paramHullRadius;
162 
164  private: int paramLengthN;
165 
167  private: Eigen::MatrixXd Ma;
168 
170  protected: std::string waveModelName;
171 
172  // /// \brief Wave parameters.
173  // private: int paramWaveN;
174 
175  // /// \brief Wave amplitude values for N components.
176  // private: std::vector<float> paramWaveAmps;
177 
178  // /// \brief Wave period values for N components.
179  // private: std::vector<float> paramWavePeriods;
180 
181  // /// \brief Wave direction values for N components.
182  // private: std::vector<std::vector<float>> paramWaveDirections;
183 
185  private: event::ConnectionPtr updateConnection;
186 
188  private: std::shared_ptr<const asv::WaveParameters> waveParams;
189  };
190 }
191 
192 #endif


usv_gazebo_plugins
Author(s): Brian Bingham , Carlos Aguero
autogenerated on Thu May 7 2020 03:54:47