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 <memory>
21
22#include <ignition/math/Vector3.hh>
23
25#include "gazebo/physics/physics.hh"
26
27namespace gazebo
28{
29 // Forward declaration
30 class WindPluginPrivate;
31
33 // The wind is described as a uniform worldwide model. So it is independant
34 // from model position for simple computations. Its components are computed
35 // separately:
36 // - Horizontal amplitude:
37 // Low pass filtering on user input (complementary gain)
38 // + small local fluctuations
39 // + noise on value (noise amplitude is a factor of wind magnitude)
40 //
41 // - Horizontal direction:
42 // Low pass filtering on user input (complementary gain)
43 // + small local fluctuations
44 // + noise on value
45 //
46 // - Vertical amplitude:
47 // Noise proportionnal to wind magnitude.
48 class GZ_PLUGIN_VISIBLE WindPlugin : public WorldPlugin
49 {
51 public: WindPlugin();
52
53 // Documentation inherited
54 public: virtual void Load(physics::WorldPtr _world, sdf::ElementPtr _sdf);
55
61 public: ignition::math::Vector3d LinearVel(
62 const physics::Wind *_wind,
63 const physics::Entity *_entity);
64
66 private: void OnUpdate();
67
70 private: std::unique_ptr<WindPluginPrivate> dataPtr;
71 };
72}
73
74#endif
A plugin that simulates a simple wind model.
Definition WindPlugin.hh:49
virtual void Load(physics::WorldPtr _world, sdf::ElementPtr _sdf)
Load function.
WindPlugin()
Constructor.
ignition::math::Vector3d LinearVel(const physics::Wind *_wind, const physics::Entity *_entity)
Get the global wind velocity.
A plugin with access to physics::World.
Definition Plugin.hh:279
Base class for all physics objects in Gazebo.
Definition Entity.hh:53
Base class for wind.
Definition Wind.hh:42
boost::shared_ptr< World > WorldPtr
Definition PhysicsTypes.hh:89
Forward declarations for the common classes.
Definition Animation.hh:27