Classes | Public Member Functions | Protected Member Functions | Private Attributes | List of all members
gazebo::UsvWindPlugin Class Reference

A plugin that simulates a simple wind model. It accepts the following parameters: More...

#include <usv_gazebo_wind_plugin.hh>

Inheritance diagram for gazebo::UsvWindPlugin:
Inheritance graph
[legend]

Classes

struct  WindObj
 

Public Member Functions

virtual void Load (physics::WorldPtr _parent, sdf::ElementPtr _sdf)
 
 UsvWindPlugin ()
 Constructor. More...
 
virtual ~UsvWindPlugin ()=default
 Destructor. More...
 

Protected Member Functions

virtual void Update ()
 Callback executed at every physics update. More...
 

Private Attributes

bool debug = true
 Bool debug set by environment var VRX_DEBUG More...
 
double filterGain
 Calculated filter gain constant. More...
 
double gainConstant
 User specified gain constant. More...
 
double lastPublishTime = 0
 Last time wind speed and direction was published. More...
 
double previousTime
 Previous time. More...
 
std::unique_ptr< std::mt19937 > randGenerator
 
std::unique_ptr< ros::NodeHandlerosNode
 ROS node handle. More...
 
double timeConstant
 Time constant. More...
 
std::string topicWindDirection = "/vrx/debug/wind/direction"
 Topic where the wind direction is published. More...
 
std::string topicWindSpeed = "/vrx/debug/wind/speed"
 Topic where the wind speed is published. More...
 
event::ConnectionPtr updateConnection
 Pointer to the update event connection. More...
 
double updateRate
 Update rate buffer for wind speed and direction. More...
 
double varVel
 Variable velocity component. More...
 
ignition::math::Vector3d windDirection
 Wind velocity unit vector in Gazebo coordinates [m/s]. More...
 
ros::Publisher windDirectionPub
 Publisher for wind direction. More...
 
double windMeanVelocity
 Average wind velocity. More...
 
std::vector< UsvWindPlugin::WindObjwindObjs
 vector of simple objects effected by the wind More...
 
bool windObjsInit = false
 Bool to keep track if ALL of the windObjs have been initialized. More...
 
unsigned int windObjsInitCount = 0
 Bool to keep track if ALL of the windObjs have been initialized. More...
 
ros::Publisher windSpeedPub
 Publisher for wind speed. More...
 
physics::WorldPtr world
 Pointer to the Gazebo world. More...
 

Detailed Description

A plugin that simulates a simple wind model. It accepts the following parameters:

<wind_objs>: Block of objects (models) to be effected by the wind. <wind_obj>: A wind object. NOTE: may include as many objects as you like <name>: Name of the model (object) that will be effected by the wind <link_name>: Link on that model which will feel the force of the wind (limited to ONE per model). <coeff_vector>: Coefficient vector of the particluar wind object.

<wind_direction>: Wind direction vector. Wind direction is specified as the positive direction of the wind velocity vector in the horizontal plane in degrees using the ENU coordinate convention

<wind_mean_velocity>: The wind average velocity.

<var_wind_gain_constants>: Variable wind speed gain constant.

<var_wind_time_constants>: Variable wind speed time constant.

<random_seed>: Set the seed for wind speed randomization.

<update_rate>: Publishing rate of the wind topic. If set to 0, it will not publish, if set to a -1 it will publish every simulation iteration. "Station-keeping control of an unmanned surface vehicle exposed to current and wind disturbances".

Definition at line 61 of file usv_gazebo_wind_plugin.hh.

Constructor & Destructor Documentation

UsvWindPlugin::UsvWindPlugin ( )

Constructor.

Definition at line 26 of file usv_gazebo_wind_plugin.cc.

virtual gazebo::UsvWindPlugin::~UsvWindPlugin ( )
virtualdefault

Destructor.

Member Function Documentation

void UsvWindPlugin::Load ( physics::WorldPtr  _parent,
sdf::ElementPtr  _sdf 
)
virtual

Definition at line 31 of file usv_gazebo_wind_plugin.cc.

void UsvWindPlugin::Update ( )
protectedvirtual

Callback executed at every physics update.

Definition at line 172 of file usv_gazebo_wind_plugin.cc.

Member Data Documentation

bool gazebo::UsvWindPlugin::debug = true
private

Bool debug set by environment var VRX_DEBUG

Definition at line 152 of file usv_gazebo_wind_plugin.hh.

double gazebo::UsvWindPlugin::filterGain
private

Calculated filter gain constant.

Definition at line 116 of file usv_gazebo_wind_plugin.hh.

double gazebo::UsvWindPlugin::gainConstant
private

User specified gain constant.

Definition at line 113 of file usv_gazebo_wind_plugin.hh.

double gazebo::UsvWindPlugin::lastPublishTime = 0
private

Last time wind speed and direction was published.

Definition at line 143 of file usv_gazebo_wind_plugin.hh.

double gazebo::UsvWindPlugin::previousTime
private

Previous time.

Definition at line 122 of file usv_gazebo_wind_plugin.hh.

std::unique_ptr<std::mt19937> gazebo::UsvWindPlugin::randGenerator
private

Definition at line 155 of file usv_gazebo_wind_plugin.hh.

std::unique_ptr<ros::NodeHandle> gazebo::UsvWindPlugin::rosNode
private

ROS node handle.

Definition at line 128 of file usv_gazebo_wind_plugin.hh.

double gazebo::UsvWindPlugin::timeConstant
private

Time constant.

Definition at line 119 of file usv_gazebo_wind_plugin.hh.

std::string gazebo::UsvWindPlugin::topicWindDirection = "/vrx/debug/wind/direction"
private

Topic where the wind direction is published.

Definition at line 140 of file usv_gazebo_wind_plugin.hh.

std::string gazebo::UsvWindPlugin::topicWindSpeed = "/vrx/debug/wind/speed"
private

Topic where the wind speed is published.

Definition at line 137 of file usv_gazebo_wind_plugin.hh.

event::ConnectionPtr gazebo::UsvWindPlugin::updateConnection
private

Pointer to the update event connection.

Definition at line 149 of file usv_gazebo_wind_plugin.hh.

double gazebo::UsvWindPlugin::updateRate
private

Update rate buffer for wind speed and direction.

Definition at line 146 of file usv_gazebo_wind_plugin.hh.

double gazebo::UsvWindPlugin::varVel
private

Variable velocity component.

Definition at line 125 of file usv_gazebo_wind_plugin.hh.

ignition::math::Vector3d gazebo::UsvWindPlugin::windDirection
private

Wind velocity unit vector in Gazebo coordinates [m/s].

Definition at line 107 of file usv_gazebo_wind_plugin.hh.

ros::Publisher gazebo::UsvWindPlugin::windDirectionPub
private

Publisher for wind direction.

Definition at line 134 of file usv_gazebo_wind_plugin.hh.

double gazebo::UsvWindPlugin::windMeanVelocity
private

Average wind velocity.

Definition at line 110 of file usv_gazebo_wind_plugin.hh.

std::vector<UsvWindPlugin::WindObj> gazebo::UsvWindPlugin::windObjs
private

vector of simple objects effected by the wind

Definition at line 95 of file usv_gazebo_wind_plugin.hh.

bool gazebo::UsvWindPlugin::windObjsInit = false
private

Bool to keep track if ALL of the windObjs have been initialized.

Definition at line 98 of file usv_gazebo_wind_plugin.hh.

unsigned int gazebo::UsvWindPlugin::windObjsInitCount = 0
private

Bool to keep track if ALL of the windObjs have been initialized.

Definition at line 101 of file usv_gazebo_wind_plugin.hh.

ros::Publisher gazebo::UsvWindPlugin::windSpeedPub
private

Publisher for wind speed.

Definition at line 131 of file usv_gazebo_wind_plugin.hh.

physics::WorldPtr gazebo::UsvWindPlugin::world
private

Pointer to the Gazebo world.

Definition at line 104 of file usv_gazebo_wind_plugin.hh.


The documentation for this class was generated from the following files:


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