Open dscherrenburg opened 8 months ago
I met similar problem as dscherrenburg described, that Wave Visual doesn't change with the parameter topic.
In the end I found out that the wave parameter only apply on wave visual once at start up, which are described in /vrx/vrx_gz/src/WaveVisual.cc, inside the member function WaveVisualPrivate::OnUpdate() and control by the paramsSet boolean. So I tried these temporary solutions to change wave parameters of wave visual:
1.Let parametset become false when receive call back from parameter topic.
Or more violence but simpler way :
if (!this->paramsSet) { }
block at line 304 of WaveVisual.cc, let params update every render cycle.Wave visual will change its parameters through these ways.
But I found out another issue that the wave visual and the buoyancy apply on the wamv or buoy are not synchronized, there are tiny phase difference between them. This behavior will more significant when using larger wave amplitude (gain). You can see the wamv doesn't move with wave visuals and "fly" out above the water line. Same in buoy. The wave parameter in this case is
public: WavefieldPrivate():
size({6000, 6000}),
cellCount({300, 300}),
model("PMS"),
number(3),
scale(1.1),
angle(0.3),
steepness(0.0),
amplitude(0.0),
period(10),
phase(0.0),
direction(0.0),
angularFrequency(2.0*M_PI),
wavelength(2 * M_PI / this->DeepWaterDispersionToWavenumber(2.0 * M_PI)),
wavenumber(this->DeepWaterDispersionToWavenumber(2.0 * M_PI)),
tau(2.0),
gain(5.0)
I change params by modifying the Wavefield.cc default value and removing parameter publisher plugin block in sydney_regatta.sdf.
I guess this might cause by renderer? Or the coast_wave glsl program?
Description of the bug I am trying to make adjustments to the wavefield to test some things about the dynamics of my vessel. Adjustments I try to make are expanding the waves and reducing or increasing the size of the wavefield. To turn off the waves I set the gain and amplitude to 0 in the sydney_regatta.sdf, see first image below. This results in the vessel no longer moving up and down as expected, but the visuals of the waves are not stopped. I'm trying to change the size of the wavefield by adding a 'size' parameter to the sydney_regatta.sdf, see first image below. The design of this is based on how this is read by the Wavefield.cc file: {params["size"].vector3d_value().x(), params["size"].vector3d_value().y()}. The adjusted values are also published correctly to the /vrx/wavefield/parameters topic as shown in the second image.
Reproduction
System Configuration:
Screenshots