usv_wind_plugin.xacro 1.05 KB
Newer Older
Ricardo Rico Uribe's avatar
Ricardo Rico Uribe committed
1
2
3
4
5
6
7
<?xml version="1.0"?>
<world xmlns:xacro="http://ros.org/wiki/xacro">
  <xacro:macro name="usv_wind_gazebo"
               params="**wind_objs
                         direction:=270
                         mean_vel:=0
                         var_gain:=0
8
                         var_time:=0
Ricardo Rico Uribe's avatar
Ricardo Rico Uribe committed
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
                         seed:=''
                         ros_update_rate:=10
                         " >
    <!--Gazebo Plugin for simulating WAM-V dynamics-->
    <plugin name="wind" filename="libusv_gazebo_wind_plugin.so">
      <!-- models to be effected by the wind -->
      <xacro:insert_block name="wind_objs"/>
      <!-- Wind -->
      <wind_direction>${direction}</wind_direction> <!-- in degrees -->
      <wind_mean_velocity>${mean_vel}</wind_mean_velocity>
      <var_wind_gain_constants>${var_gain}</var_wind_gain_constants>
      <var_wind_time_constants>${var_time}</var_wind_time_constants>
      <random_seed>${seed}</random_seed> <!-- set to zero/empty to randomize -->
      <update_rate>${ros_update_rate}</update_rate>
    </plugin>
  </xacro:macro>
</world>