Before this patch, all the plugins using a wave field needed to have the same <wavefield> SDF parameter block in its SDF plugin definition. This pull request changes this behavior by:
Setting one of the plugins to operate as the primary. The primary plugin requires to specify all the <wavefield> parameters as usual. Then, it should periodically publish the wavefield parameters via Transport.
The rest of the plugins should be set to operate as secondary. This means passing only one parameters inside the <wavefield> block. This parameters is the topic name where the wave field parameters are sent. When received, the wavefield can be populated with a new helper function.
Our WaveVisual plugin is set to operate as the primary. All the instances of Surface and PolyhedreaBuoyancyDrag plugins are set to operate as secondary.
and verify that the buoys and the WAM-V move a bit up and down.
You can modify vrx_gz/worlds/stationkeeping_task.sdf:
<!-- The wave field -->
<plugin filename="libPublisherPlugin.so" name="vrx::PublisherPlugin">
<message type="gz.msgs.Param" topic="/vrx/wavefield/parameters"
every="2.0">
...
params {
key: "gain"
value {
type: DOUBLE
double_value: 0.1
}
}
...
</message>
</plugin>
Recompile and launch the simulation again. You should verify now that the WAM-V and the buoys stay flat at the water surface.
[Edit: updated test instructions]
@M1chaelM , as we discussed offline, I've created a PublishPlugin to publish the wave field parameters every 2 seconds. All worlds in this PR use this plugin now. This is good to go for a review.
Fixes #564 using Gazebo Transport.
Before this patch, all the plugins using a wave field needed to have the same
<wavefield>
SDF parameter block in its SDF plugin definition. This pull request changes this behavior by:primary
. Theprimary
plugin requires to specify all the<wavefield>
parameters as usual. Then, it should periodically publish the wavefield parameters via Transport.secondary
. This means passing only one parameters inside the<wavefield>
block. This parameters is the topic name where the wave field parameters are sent. When received, the wavefield can be populated with a new helper function.Our
WaveVisual
plugin is set to operate as the primary. All the instances ofSurface
andPolyhedreaBuoyancyDrag
plugins are set to operate as secondary.How to test it?
and verify that the buoys and the WAM-V move a bit up and down.
vrx_gz/worlds/stationkeeping_task.sdf
:Recompile and launch the simulation again. You should verify now that the WAM-V and the buoys stay flat at the water surface. [Edit: updated test instructions]