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

This gazebo plugin simulates wind acting on a model. More...

#include <gazebo_wind_plugin.h>

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

Public Member Functions

 GazeboWindPlugin ()
 
virtual ~GazeboWindPlugin ()
 

Protected Member Functions

void Load (physics::ModelPtr _model, sdf::ElementPtr _sdf)
 Load the plugin. More...
 
void OnUpdate (const common::UpdateInfo &)
 Called when the world is updated. More...
 

Private Member Functions

ignition::math::Vector3d BilinearInterpolation (double *position, ignition::math::Vector3d *values, double *points) const
 Bilinear interpolation. More...
 
void CreatePubsAndSubs ()
 Creates all required publishers and subscribers, incl. routing of messages to/from ROS if required. More...
 
ignition::math::Vector3d LinearInterpolation (double position, ignition::math::Vector3d *values, double *points) const
 Functions for trilinear interpolation of wind field at aircraft position. More...
 
void ReadCustomWindField (std::string &custom_wind_field_path)
 Reads wind data from a text file and saves it. More...
 
ignition::math::Vector3d TrilinearInterpolation (ignition::math::Vector3d link_position, ignition::math::Vector3d *values, double *points) const
 Trilinear interpolation. More...
 

Private Attributes

std::vector< floatbottom_z_
 
std::string frame_id_
 
physics::LinkPtr link_
 
std::string link_name_
 
float min_x_
 
float min_y_
 
physics::ModelPtr model_
 
int n_x_
 
int n_y_
 
std::string namespace_
 
gazebo::transport::NodePtr node_handle_
 
bool pubs_and_subs_created_
 Flag that is set to true once CreatePubsAndSubs() is called, used to prevent CreatePubsAndSubs() from be called on every OnUpdate(). More...
 
float res_x_
 
float res_y_
 
std::vector< floattop_z_
 
std::vector< floatu_
 
event::ConnectionPtr update_connection_
 Pointer to the update event connection. More...
 
bool use_custom_static_wind_field_
 Variables for custom wind field generation. More...
 
std::vector< floatv_
 
std::vector< floatvertical_spacing_factors_
 
std::vector< floatw_
 
ignition::math::Vector3d wind_direction_
 
double wind_force_mean_
 
gazebo::transport::PublisherPtr wind_force_pub_
 
std::string wind_force_pub_topic_
 
double wind_force_variance_
 
ignition::math::Vector3d wind_gust_direction_
 
common::Time wind_gust_end_
 
double wind_gust_force_mean_
 
double wind_gust_force_variance_
 
common::Time wind_gust_start_
 
double wind_speed_mean_
 
gz_mav_msgs::WindSpeed wind_speed_msg_
 Gazebo message for sending wind speed data. More...
 
gazebo::transport::PublisherPtr wind_speed_pub_
 
std::string wind_speed_pub_topic_
 
double wind_speed_variance_
 
physics::WorldPtr world_
 
gz_geometry_msgs::WrenchStamped wrench_stamped_msg_
 Gazebo message for sending wind data. More...
 
ignition::math::Vector3d xyz_offset_
 

Detailed Description

This gazebo plugin simulates wind acting on a model.

This plugin publishes on a Gazebo topic and instructs the ROS interface plugin to forward the message onto ROS.

Definition at line 67 of file gazebo_wind_plugin.h.

Constructor & Destructor Documentation

◆ GazeboWindPlugin()

gazebo::GazeboWindPlugin::GazeboWindPlugin ( )
inline

Definition at line 69 of file gazebo_wind_plugin.h.

◆ ~GazeboWindPlugin()

gazebo::GazeboWindPlugin::~GazeboWindPlugin ( )
virtual

Definition at line 31 of file gazebo_wind_plugin.cpp.

Member Function Documentation

◆ BilinearInterpolation()

ignition::math::Vector3d gazebo::GazeboWindPlugin::BilinearInterpolation ( double *  position,
ignition::math::Vector3d *  values,
double *  points 
) const
private

Bilinear interpolation.

Parameters
[in]positionPointer to an array of size 2 containing the x- and y-coordinates of the target point. values Pointer to an array of size 4 containing the wind values of the four points to interpolate from (8, 9, 10 and 11). points Pointer to an array of size 14 containing the z-coordinate of the eight points to interpolate from, the x-coordinate of the four intermediate points (8, 9, 10 and 11), and the y-coordinate of the last two intermediate points (12 and 13).

Definition at line 416 of file gazebo_wind_plugin.cpp.

◆ CreatePubsAndSubs()

void gazebo::GazeboWindPlugin::CreatePubsAndSubs ( )
private

Creates all required publishers and subscribers, incl. routing of messages to/from ROS if required.

Call this once the first time OnUpdate() is called (can't be called from Load() because there is no guarantee GazeboRosInterfacePlugin has has loaded and listening to ConnectGazeboToRosTopic and ConnectRosToGazeboTopic messages).

Definition at line 300 of file gazebo_wind_plugin.cpp.

◆ LinearInterpolation()

ignition::math::Vector3d gazebo::GazeboWindPlugin::LinearInterpolation ( double  position,
ignition::math::Vector3d *  values,
double *  points 
) const
private

Functions for trilinear interpolation of wind field at aircraft position.

Linear interpolation

Parameters
[in]positiony-coordinate of the target point. values Pointer to an array of size 2 containing the wind values of the two points to interpolate from (12 and 13). points Pointer to an array of size 2 containing the y-coordinate of the two points to interpolate from.

Definition at line 409 of file gazebo_wind_plugin.cpp.

◆ Load()

void gazebo::GazeboWindPlugin::Load ( physics::ModelPtr  _model,
sdf::ElementPtr  _sdf 
)
protected

Load the plugin.

Parameters
[in]_modelPointer to the model that loaded this plugin.
[in]_sdfSDF element that describes the plugin.

Definition at line 35 of file gazebo_wind_plugin.cpp.

◆ OnUpdate()

void gazebo::GazeboWindPlugin::OnUpdate ( const common::UpdateInfo &  _info)
protected

Called when the world is updated.

Parameters
[in]_infoUpdate timing information.

Definition at line 126 of file gazebo_wind_plugin.cpp.

◆ ReadCustomWindField()

void gazebo::GazeboWindPlugin::ReadCustomWindField ( std::string &  custom_wind_field_path)
private

Reads wind data from a text file and saves it.

Parameters
[in]custom_wind_field_pathPath to the wind field from ~/.ros.

Definition at line 340 of file gazebo_wind_plugin.cpp.

◆ TrilinearInterpolation()

ignition::math::Vector3d gazebo::GazeboWindPlugin::TrilinearInterpolation ( ignition::math::Vector3d  link_position,
ignition::math::Vector3d *  values,
double *  points 
) const
private

Trilinear interpolation.

Parameters
[in]link_positionVector3 containing the x, y and z-coordinates of the target point. values Pointer to an array of size 8 containing the wind values of the eight points to interpolate from (0, 1, 2, 3, 4, 5, 6 and 7). points Pointer to an array of size 14 containing the z-coordinate of the eight points to interpolate from, the x-coordinate of the four intermediate points (8, 9, 10 and 11), and the y-coordinate of the last two intermediate points (12 and 13).

Definition at line 427 of file gazebo_wind_plugin.cpp.

Member Data Documentation

◆ bottom_z_

std::vector<float> gazebo::GazeboWindPlugin::bottom_z_
private

Definition at line 150 of file gazebo_wind_plugin.h.

◆ frame_id_

std::string gazebo::GazeboWindPlugin::frame_id_
private

Definition at line 122 of file gazebo_wind_plugin.h.

◆ link_

physics::LinkPtr gazebo::GazeboWindPlugin::link_
private

Definition at line 118 of file gazebo_wind_plugin.h.

◆ link_name_

std::string gazebo::GazeboWindPlugin::link_name_
private

Definition at line 123 of file gazebo_wind_plugin.h.

◆ min_x_

float gazebo::GazeboWindPlugin::min_x_
private

Definition at line 143 of file gazebo_wind_plugin.h.

◆ min_y_

float gazebo::GazeboWindPlugin::min_y_
private

Definition at line 144 of file gazebo_wind_plugin.h.

◆ model_

physics::ModelPtr gazebo::GazeboWindPlugin::model_
private

Definition at line 117 of file gazebo_wind_plugin.h.

◆ n_x_

int gazebo::GazeboWindPlugin::n_x_
private

Definition at line 145 of file gazebo_wind_plugin.h.

◆ n_y_

int gazebo::GazeboWindPlugin::n_y_
private

Definition at line 146 of file gazebo_wind_plugin.h.

◆ namespace_

std::string gazebo::GazeboWindPlugin::namespace_
private

Definition at line 120 of file gazebo_wind_plugin.h.

◆ node_handle_

gazebo::transport::NodePtr gazebo::GazeboWindPlugin::node_handle_
private

Definition at line 195 of file gazebo_wind_plugin.h.

◆ pubs_and_subs_created_

bool gazebo::GazeboWindPlugin::pubs_and_subs_created_
private

Flag that is set to true once CreatePubsAndSubs() is called, used to prevent CreatePubsAndSubs() from be called on every OnUpdate().

Definition at line 105 of file gazebo_wind_plugin.h.

◆ res_x_

float gazebo::GazeboWindPlugin::res_x_
private

Definition at line 147 of file gazebo_wind_plugin.h.

◆ res_y_

float gazebo::GazeboWindPlugin::res_y_
private

Definition at line 148 of file gazebo_wind_plugin.h.

◆ top_z_

std::vector<float> gazebo::GazeboWindPlugin::top_z_
private

Definition at line 151 of file gazebo_wind_plugin.h.

◆ u_

std::vector<float> gazebo::GazeboWindPlugin::u_
private

Definition at line 152 of file gazebo_wind_plugin.h.

◆ update_connection_

event::ConnectionPtr gazebo::GazeboWindPlugin::update_connection_
private

Pointer to the update event connection.

Definition at line 114 of file gazebo_wind_plugin.h.

◆ use_custom_static_wind_field_

bool gazebo::GazeboWindPlugin::use_custom_static_wind_field_
private

Variables for custom wind field generation.

Definition at line 142 of file gazebo_wind_plugin.h.

◆ v_

std::vector<float> gazebo::GazeboWindPlugin::v_
private

Definition at line 153 of file gazebo_wind_plugin.h.

◆ vertical_spacing_factors_

std::vector<float> gazebo::GazeboWindPlugin::vertical_spacing_factors_
private

Definition at line 149 of file gazebo_wind_plugin.h.

◆ w_

std::vector<float> gazebo::GazeboWindPlugin::w_
private

Definition at line 154 of file gazebo_wind_plugin.h.

◆ wind_direction_

ignition::math::Vector3d gazebo::GazeboWindPlugin::wind_direction_
private

Definition at line 135 of file gazebo_wind_plugin.h.

◆ wind_force_mean_

double gazebo::GazeboWindPlugin::wind_force_mean_
private

Definition at line 127 of file gazebo_wind_plugin.h.

◆ wind_force_pub_

gazebo::transport::PublisherPtr gazebo::GazeboWindPlugin::wind_force_pub_
private

Definition at line 192 of file gazebo_wind_plugin.h.

◆ wind_force_pub_topic_

std::string gazebo::GazeboWindPlugin::wind_force_pub_topic_
private

Definition at line 124 of file gazebo_wind_plugin.h.

◆ wind_force_variance_

double gazebo::GazeboWindPlugin::wind_force_variance_
private

Definition at line 128 of file gazebo_wind_plugin.h.

◆ wind_gust_direction_

ignition::math::Vector3d gazebo::GazeboWindPlugin::wind_gust_direction_
private

Definition at line 136 of file gazebo_wind_plugin.h.

◆ wind_gust_end_

common::Time gazebo::GazeboWindPlugin::wind_gust_end_
private

Definition at line 138 of file gazebo_wind_plugin.h.

◆ wind_gust_force_mean_

double gazebo::GazeboWindPlugin::wind_gust_force_mean_
private

Definition at line 129 of file gazebo_wind_plugin.h.

◆ wind_gust_force_variance_

double gazebo::GazeboWindPlugin::wind_gust_force_variance_
private

Definition at line 130 of file gazebo_wind_plugin.h.

◆ wind_gust_start_

common::Time gazebo::GazeboWindPlugin::wind_gust_start_
private

Definition at line 139 of file gazebo_wind_plugin.h.

◆ wind_speed_mean_

double gazebo::GazeboWindPlugin::wind_speed_mean_
private

Definition at line 131 of file gazebo_wind_plugin.h.

◆ wind_speed_msg_

gz_mav_msgs::WindSpeed gazebo::GazeboWindPlugin::wind_speed_msg_
private

Gazebo message for sending wind speed data.

This is defined at the class scope so that it is re-created everytime a wind speed message needs to be sent, increasing performance.

Definition at line 205 of file gazebo_wind_plugin.h.

◆ wind_speed_pub_

gazebo::transport::PublisherPtr gazebo::GazeboWindPlugin::wind_speed_pub_
private

Definition at line 193 of file gazebo_wind_plugin.h.

◆ wind_speed_pub_topic_

std::string gazebo::GazeboWindPlugin::wind_speed_pub_topic_
private

Definition at line 125 of file gazebo_wind_plugin.h.

◆ wind_speed_variance_

double gazebo::GazeboWindPlugin::wind_speed_variance_
private

Definition at line 132 of file gazebo_wind_plugin.h.

◆ world_

physics::WorldPtr gazebo::GazeboWindPlugin::world_
private

Definition at line 116 of file gazebo_wind_plugin.h.

◆ wrench_stamped_msg_

gz_geometry_msgs::WrenchStamped gazebo::GazeboWindPlugin::wrench_stamped_msg_
private

Gazebo message for sending wind data.

This is defined at the class scope so that it is re-created everytime a wind message needs to be sent, increasing performance.

Definition at line 200 of file gazebo_wind_plugin.h.

◆ xyz_offset_

ignition::math::Vector3d gazebo::GazeboWindPlugin::xyz_offset_
private

Definition at line 134 of file gazebo_wind_plugin.h.


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


rotors_gazebo_plugins
Author(s): Fadri Furrer, Michael Burri, Mina Kamel, Janosch Nikolic, Markus Achtelik
autogenerated on Mon Feb 28 2022 23:39:04