WindPlugin.hh
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2016 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_PLUGINS_WINDPLUGIN_HH_
18 #define GAZEBO_PLUGINS_WINDPLUGIN_HH_
19 
20 #include <ignition/math/Vector3.hh>
21 
22 #include "gazebo/common/Event.hh"
23 #include "gazebo/common/Plugin.hh"
24 #include "gazebo/physics/physics.hh"
25 #include "gazebo/sensors/Noise.hh"
26 
27 namespace gazebo
28 {
30  // The wind is described as a uniform worldwide model. So it is independant
31  // from model position for simple computations. Its components are computed
32  // separately:
33  // - Horizontal amplitude:
34  // Low pass filtering on user input (complementary gain)
35  // + small local fluctuations
36  // + noise on value (noise amplitude is a factor of wind magnitude)
37  //
38  // - Horizontal direction:
39  // Low pass filtering on user input (complementary gain)
40  // + small local fluctuations
41  // + noise on value
42  //
43  // - Vertical amplitude:
44  // Noise proportionnal to wind magnitude.
46  {
48  public: WindPlugin();
49 
50  // Documentation inherited
51  public: virtual void Load(physics::WorldPtr _world, sdf::ElementPtr _sdf);
52 
58  public: ignition::math::Vector3d LinearVel(
59  const physics::Wind *_wind,
60  const physics::Entity *_entity);
61 
63  private: void OnUpdate();
64 
66  private: physics::WorldPtr world;
67 
69  private: event::ConnectionPtr updateConnection;
70 
72  private: double characteristicTimeForWindRise = 1;
73 
75  private: double magnitudeSinAmplitudePercent = 0;
76 
78  private: double magnitudeSinPeriod = 1;
79 
81  private: double characteristicTimeForWindOrientationChange = 1;
82 
84  private: double orientationSinAmplitude = 0;
85 
87  private: double orientationSinPeriod = 1;
88 
90  private: double kMag = 0;
91 
93  private: double kDir = 0;
94 
96  private: double magnitudeMean = 0;
97 
99  private: double directionMean = 0;
100 
102  private: sensors::NoisePtr noiseMagnitude;
103 
105  private: sensors::NoisePtr noiseDirection;
106 
108  private: sensors::NoisePtr noiseVertical;
109  };
110 }
111 
112 #endif
std::shared_ptr< Noise > NoisePtr
Definition: SensorTypes.hh:124
boost::shared_ptr< World > WorldPtr
Definition: PhysicsTypes.hh:89
A plugin that simulates a simple wind model.
Definition: WindPlugin.hh:45
A plugin with access to physics::World.
Definition: Plugin.hh:235
Base class for wind.
Definition: Wind.hh:41
boost::shared_ptr< Connection > ConnectionPtr
Definition: CommonTypes.hh:134
Base class for all physics objects in Gazebo.
Definition: Entity.hh:52
#define GAZEBO_VISIBLE
Use to represent "symbol visible" if supported.
Definition: system.hh:59