WavefieldVisualPlugin.cc
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2019 Rhys Mainwaring
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9  *
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  *
16 */
17 
18 #include <memory>
19 #include <thread>
20 #include <vector>
21 
22 #include <gazebo/gazebo.hh>
23 #include <gazebo/common/Event.hh>
24 #include <gazebo/common/Time.hh>
25 #include <gazebo/common/Plugin.hh>
26 #include <gazebo/rendering/rendering.hh>
27 #include <gazebo/rendering/RenderTypes.hh>
28 #include <gazebo/rendering/Scene.hh>
29 #include <gazebo/rendering/Visual.hh>
30 #include <gazebo/sensors/Sensor.hh>
31 #include <gazebo/sensors/SensorManager.hh>
32 #include <gazebo/transport/transport.hh>
33 #include <gazebo/transport/Node.hh>
34 
35 #include <ignition/math/Vector2.hh>
36 #include <ignition/math/Vector3.hh>
37 
38 #include "gazebo/rendering/ogre_gazebo.h"
39 #include "gazebo/rendering/Camera.hh"
40 #include "gazebo/rendering/UserCamera.hh"
41 
46 
47 using namespace gazebo;
48 
49 namespace asv
50 {
51  GZ_REGISTER_VISUAL_PLUGIN(WavefieldVisualPlugin)
52 
53 // Utilties
55 
56 
57  void ToOgreVector2(const std::vector<double>& _v, Ogre::Vector2& _vout)
61  {
62  _vout = Ogre::Vector2::ZERO;
63  if (_v.size() > 2)
64  {
65  gzerr << "Vector must have size 2 or less" << std::endl;
66  return;
67  }
68  for (size_t i = 0; i < _v.size(); ++i)
69  {
70  _vout[i] = _v[i];
71  }
72  }
73 
78  void ToOgreVector3(const std::vector<double>& _v, Ogre::Vector3& _vout)
79  {
80  _vout = Ogre::Vector3::ZERO;
81  if (_v.size() > 3)
82  {
83  gzerr << "Vector must have size 3 or less" << std::endl;
84  return;
85  }
86  for (size_t i = 0; i < _v.size(); ++i)
87  {
88  _vout[i] = _v[i];
89  }
90  }
91 
96  void ToOgreVector2(const ignition::math::Vector2d& _v, Ogre::Vector2& _vout)
97  {
98  _vout.x = _v.X();
99  _vout.y = _v.Y();
100  }
101 
106  void ToOgreVector3(const ignition::math::Vector3d& _v, Ogre::Vector3& _vout)
107  {
108  _vout.x = _v.X();
109  _vout.y = _v.Y();
110  _vout.z = _v.Z();
111  }
112 
114  const std::vector<ignition::math::Vector2d>& _v,
115  Ogre::Vector2& _vout0,
116  Ogre::Vector2& _vout1,
117  Ogre::Vector2& _vout2
118  )
119  {
120  _vout0 = Ogre::Vector2::ZERO;
121  _vout1 = Ogre::Vector2::ZERO;
122  _vout2 = Ogre::Vector2::ZERO;
123 
124  if (_v.size() > 3)
125  {
126  gzerr << "Vector must have size 3 or less" << std::endl;
127  return;
128  }
129  if (_v.size() > 0)
130  ToOgreVector2(_v[0], _vout0);
131  if (_v.size() > 1)
132  ToOgreVector2(_v[1], _vout1);
133  if (_v.size() > 2)
134  ToOgreVector2(_v[2], _vout2);
135  }
136 
138  const std::vector<ignition::math::Vector3d>& _v,
139  Ogre::Vector3& _vout0,
140  Ogre::Vector3& _vout1,
141  Ogre::Vector3& _vout2
142  )
143  {
144  _vout0 = Ogre::Vector3::ZERO;
145  _vout1 = Ogre::Vector3::ZERO;
146  _vout2 = Ogre::Vector3::ZERO;
147 
148  if (_v.size() > 3)
149  {
150  gzerr << "Vector must have size 3 or less" << std::endl;
151  return;
152  }
153  if (_v.size() > 0)
154  ToOgreVector3(_v[0], _vout0);
155  if (_v.size() > 1)
156  ToOgreVector3(_v[1], _vout1);
157  if (_v.size() > 2)
158  ToOgreVector3(_v[2], _vout2);
159  }
160 
162 // WavefieldVisualPluginPrivate
163 
167  {
169  planeUp("planeUp"),
170  planeDown("planeDown")
171  {}
172 
174  public: rendering::VisualPtr visual;
175 
177  public: std::string visualName;
178 
180  public: sdf::ElementPtr sdf;
181 
183  public: std::shared_ptr<WaveParameters> waveParams;
184 
186  public: bool isStatic = false;
187 
189  public: bool enableRtt = true;
190 
193  public: double refractOpacity = 0;
194 
197  public: double reflectOpacity = 0;
198 
200  public: double rttNoise = 0;
201 
203  public: double simTime = 0;
204 
206  public: bool isInitialised = false;
207 
208  // OGRE objects for reflection/refraction
209  public: gazebo::rendering::ScenePtr scene;
210  public: Ogre::Entity* oceanEntity = nullptr;
211  public: Ogre::MovablePlane planeUp;
212  public: Ogre::MovablePlane planeDown;
213  public: Ogre::TextureUnitState *reflectTex = nullptr;
214  public: Ogre::TextureUnitState *refractTex = nullptr;
215 
216  // Vectors of OGRE objects
217  public: std::vector<Ogre::Camera*> cameras;
218  public: std::vector<Ogre::RenderTarget*> reflectionRts;
219  public: std::vector<Ogre::RenderTarget*> refractionRts;
220 
222  public: event::ConnectionPtr preRenderConnection;
223  public: event::ConnectionPtr cameraPreRenderConnection;
224  };
225 
227 // WavefieldVisualPlugin
228 
229  WavefieldVisualPlugin::~WavefieldVisualPlugin()
230  {
231  // Clean up.
232  this->data->waveParams.reset();
233 
234  // Reset connections and transport.
235  this->data->preRenderConnection.reset();
236  this->data->cameraPreRenderConnection.reset();
237  }
238 
239  WavefieldVisualPlugin::WavefieldVisualPlugin() :
240  VisualPlugin(),
241  RenderTargetListener(),
243  {
244  this->data->isInitialised = false;
245  }
246 
248  rendering::VisualPtr _visual,
249  sdf::ElementPtr _sdf)
250  {
251  // @DEBUG_INFO
252  // std::thread::id threadId = std::this_thread::get_id();
253  // gzmsg << "Load WavefieldVisualPlugin [thread: "
254  // << threadId << "]" << std::endl;
255 
256  // Capture visual and plugin SDF
257  GZ_ASSERT(_visual != nullptr, "Visual must not be null");
258  GZ_ASSERT(_sdf != nullptr, "SDF Element must not be null");
259 
260  // Capture the visual and sdf.
261  this->data->visual = _visual;
262  this->data->sdf = _sdf;
263 
264  // Process SDF Parameters
265  #if GAZEBO_MAJOR_VERSION >= 8
266  this->data->visualName = _visual->Name();
267  #else
268  this->data->visualName = _visual->GetName();
269  #endif
270 
271  gzmsg << "WavefieldVisualPlugin <" << this->data->visualName
272  << ">: Loading WaveParamaters from SDF" << std::endl;
273 
274  this->data->isStatic = Utilities::SdfParamBool(*_sdf, "static", false);
275 
276 #if (GAZEBO_MAJOR_VERSION == 7 && GAZEBO_MINOR_VERSION >= 16) || \
277  (GAZEBO_MAJOR_VERSION == 9 && GAZEBO_MINOR_VERSION >= 11)
278  // Check if reflection/refracion rtts enabled
279  // Only available in Gazebo Version >=7.16.0 || >=9.11.0
280  this->data->enableRtt = Utilities::SdfParamBool(*_sdf, "enableRtt", true);
281 #else
282  this->data->enableRtt = false;
283 #endif
284 
285  // Read refraction and reflection ratios and noise
286  this->data->refractOpacity =
287  Utilities::SdfParamDouble(*_sdf, "refractOpacity", 0.2);
288  this->data->reflectOpacity =
289  Utilities::SdfParamDouble(*_sdf, "reflectOpacity", 0.2);
290  this->data->rttNoise =
291  Utilities::SdfParamDouble(*_sdf, "rttNoise", 0.1);
292 
293  this->data->waveParams.reset(new WaveParameters());
294  if (_sdf->HasElement("wave"))
295  {
296  gzmsg << "Found <wave> tag" << std::endl;
297  sdf::ElementPtr sdfWave = _sdf->GetElement("wave");
298  this->data->waveParams->SetFromSDF(*sdfWave);
299  }
300  else
301  {
302  gzerr << "Missing <wave> tag" << std::endl;
303  }
304 
305  // @DEBUG_INFO
306  this->data->waveParams->DebugPrint();
307 
308  // Setup oceanEntity
309  Ogre::SceneNode *ogreNode = this->data->visual->GetSceneNode();
310  this->data->oceanEntity =
311  dynamic_cast<Ogre::Entity *>(ogreNode->getAttachedObject(0));
312  if (!this->data->oceanEntity)
313  {
314  gzerr << "No ocean entity found" << std::endl;
315  return;
316  }
317 
318  // Render water later for proper rendering of propeller
319  this->data->oceanEntity->setRenderQueueGroup(this->data->oceanEntity->
320  getRenderQueueGroup()+1);
321 
322  // Setup reflection refraction
323  if (this->data->enableRtt)
325 
326  // Bind the update method to ConnectPreRender events
327  this->data->preRenderConnection = event::Events::ConnectPreRender(
328  std::bind(&WavefieldVisualPlugin::OnPreRender, this));
329  }
330 
332  {
333  // @DEBUG_INFO
334  // std::thread::id threadId = std::this_thread::get_id();
335  // gzmsg << "Init WavefieldVisualPlugin [thread: "
336  // << threadId << "]" << std::endl;
337 
338  if (!this->data->isInitialised)
339  {
340  // Initialise vertex shader
341  std::string shaderType = "vertex";
342 #if 0
343  this->data->visual->SetMaterialShaderParam(
344  "time", shaderType, std::to_string(0.0));
345 #else
347  "time", shaderType, std::to_string(0.0));
348 #endif
349  this->SetShaderParams();
350 
351  this->data->isInitialised = true;
352  }
353  }
354 
356  {
357  // @DEBUG_INFO
358  // gzmsg << "Reset WavefieldVisualPlugin" << std::endl;
359  }
360 
362  {
363  if (this->data->enableRtt)
364  {
365  // Update reflection/refraction clip plane pose (in case the ocean moves)
366  this->UpdateClipPlanes();
367 
368  // Continuously look for new cameras for reflection/refraction setup
370  }
371 
372  // Create moving ocean waves
373  if (!this->data->isStatic)
374  {
375 #if 0
376  this->data->visual->SetMaterialShaderParam(
377  "time", shaderType, std::to_string(simTime));
378 #else
379  auto simTime = this->data->visual->GetScene()->SimTime();
381  "time", "vertex",
382  std::to_string(static_cast<float>(simTime.Double())));
383 #endif
384  }
385  }
386 
388 // Reflection/Refraction setup and texture creation
389 
391  {
392  // OGRE setup
393  this->data->scene = this->data->visual->GetScene();
394 
395  // Create clipping planes to hide objects for making rtts, in default pose
396  this->data->planeUp = Ogre::MovablePlane(Ogre::Vector3::UNIT_Z,
397  Ogre::Vector3::ZERO);
398  this->data->planeDown = Ogre::MovablePlane(-Ogre::Vector3::UNIT_Z,
399  Ogre::Vector3::ZERO);
400 
401  // Get texture unit states to update with rtts
402  Ogre::MaterialPtr material =
403  Ogre::MaterialManager::getSingleton().getByName(this->data->visual->
404  GetMaterialName());
405  this->data->reflectTex = (material->getTechnique(0)->getPass(0)->
406  getTextureUnitState(2));
407 
408  this->data->refractTex = (material->getTechnique(0)->getPass(0)->
409  getTextureUnitState(3));
410 
411  // Set reflection/refraction parameters
413  "refractOpacity", "fragment",
414  std::to_string(static_cast<float>(this->data->refractOpacity)));
416  "reflectOpacity", "fragment",
417  std::to_string(static_cast<float>(this->data->reflectOpacity)));
419  "rttNoise", "fragment",
420  std::to_string(static_cast<float>(this->data->rttNoise)));
421 
422  // Temp fix for camera sensors rendering upsidedown, only needed on server
423  if (this->data->scene->UserCameraCount() > 0)
424  {
426  "flipAcrossY", "fragment",
427  std::to_string(0));
428  }
429  else
430  {
432  "flipAcrossY", "fragment",
433  std::to_string(1));
434  }
435 
436 #if (GAZEBO_MAJOR_VERSION == 7 && GAZEBO_MINOR_VERSION >= 16) || \
437  (GAZEBO_MAJOR_VERSION == 9 && GAZEBO_MINOR_VERSION >= 11)
438  // Bind the update method to ConnectCameraPreRender events
439  // Only in Gazebo Version >=7.19.0 || >=9.11.0
440  this->data->cameraPreRenderConnection =
441  rendering::Events::ConnectCameraPreRender(
443  this, std::placeholders::_1));
444 #endif
445  }
446 
448  {
449  #if GAZEBO_MAJOR_VERSION >= 8
450  ignition::math::Pose3d pose = this->data->visual->WorldPose();
451  Ogre::Vector3 oceanPosition(pose.Pos().X(),
452  pose.Pos().Y(),
453  pose.Pos().Z());
454 
455  Ogre::Quaternion oceanRotation(pose.Rot().W(),
456  pose.Rot().X(),
457  pose.Rot().Y(),
458  pose.Rot().Z());
459  #else
460  math::Pose pose = this->data->visual->GetWorldPose();
461  Ogre::Vector3 oceanPosition(pose.pos.x,
462  pose.pos.y,
463  pose.pos.z);
464 
465  Ogre::Quaternion oceanRotation(pose.rot.w,
466  pose.rot.x,
467  pose.rot.y,
468  pose.rot.z);
469  #endif
470  Ogre::Vector3 oceanNormal = oceanRotation * Ogre::Vector3::UNIT_Z;
471  this->data->planeUp.redefine(oceanNormal, oceanPosition);
472  this->data->planeDown.redefine(-oceanNormal, oceanPosition);
473  }
474 
476  {
477  // User cam setup in gzclient
478  if (this->data->scene->UserCameraCount() > 0)
479  {
480  // Get user cam
481  rendering::UserCameraPtr userCamera = this->data->scene->GetUserCamera(0);
482 
483  // If user cam not already in cameras, create its rtts
484  if (std::find(this->data->cameras.begin(), this->data->cameras.end(),
485  userCamera->OgreCamera()) == this->data->cameras.end())
486  {
487  this->CreateRtts(userCamera->OgreCamera());
488  }
489  }
490 
491  // Camera sensor setup in gzserver
492  else
493  {
494  // Get new cameras, create their rtts
495  std::vector<rendering::CameraPtr> newCameras = this->NewCameras();
496  for (rendering::CameraPtr c : newCameras)
497  {
498  this->CreateRtts(c->OgreCamera());
499  }
500  }
501  }
502 
503  void WavefieldVisualPlugin::CreateRtts(Ogre::Camera* _camera)
504  {
505  // Preserve the camera aspect ratio in the texture.
506  const double kScale = 0.25;
507  const int kWidth = _camera->getViewport()->getActualWidth() * kScale;
508  const int kHeight = _camera->getViewport()->getActualHeight() * kScale;
509 
510  // Create reflection texture
511  Ogre::TexturePtr rttReflectionTexture =
512  Ogre::TextureManager::getSingleton().createManual(
513  this->data->visualName + "_" + _camera->getName() + "_reflection",
514  Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME,
515  Ogre::TEX_TYPE_2D,
516  kWidth, kHeight,
517  0,
518  Ogre::PF_R8G8B8,
519  Ogre::TU_RENDERTARGET);
520 
521  // Create refraction texture
522  Ogre::TexturePtr rttRefractionTexture =
523  Ogre::TextureManager::getSingleton().createManual(
524  this->data->visualName + "_" + _camera->getName() + "_refraction",
525  Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME,
526  Ogre::TEX_TYPE_2D,
527  kWidth, kHeight,
528  0,
529  Ogre::PF_R8G8B8,
530  Ogre::TU_RENDERTARGET);
531 
532  Ogre::ColourValue backgroundColor =
533  rendering::Conversions::Convert(this->data->scene->BackgroundColor());
534 
535  // Setup reflection render target
536  Ogre::RenderTarget* reflectionRt =
537  rttReflectionTexture->getBuffer()->getRenderTarget();
538  reflectionRt->setAutoUpdated(false);
539  Ogre::Viewport *reflVp =
540  reflectionRt->addViewport(_camera);
541  reflVp->setClearEveryFrame(true);
542  reflVp->setOverlaysEnabled(false);
543  reflVp->setBackgroundColour(backgroundColor);
544  reflVp->setVisibilityMask(GZ_VISIBILITY_ALL &
545  ~(GZ_VISIBILITY_GUI | GZ_VISIBILITY_SELECTABLE));
546  reflectionRt->addListener(this);
547 
548  // Setup refraction render target
549  Ogre::RenderTarget* refractionRt =
550  rttRefractionTexture->getBuffer()->getRenderTarget();
551  refractionRt->setAutoUpdated(false);
552  Ogre::Viewport *refrVp =
553  refractionRt->addViewport(_camera);
554  refrVp->setClearEveryFrame(true);
555  refrVp->setOverlaysEnabled(false);
556  refrVp->setBackgroundColour(backgroundColor);
557  refrVp->setVisibilityMask(GZ_VISIBILITY_ALL &
558  ~(GZ_VISIBILITY_GUI | GZ_VISIBILITY_SELECTABLE));
559  refractionRt->addListener(this);
560 
561  // Store camera and rtts
562  this->data->cameras.push_back(_camera);
563  this->data->reflectionRts.push_back(reflectionRt);
564  this->data->refractionRts.push_back(refractionRt);
565 
566  // Add frame to texture units
567  this->data->reflectTex->addFrameTextureName(rttReflectionTexture
568  ->getName());
569  this->data->refractTex->addFrameTextureName(rttRefractionTexture
570  ->getName());
571  }
572 
573  std::vector<rendering::CameraPtr> WavefieldVisualPlugin::NewCameras()
574  {
575  std::vector<rendering::CameraPtr> retVal;
576 
577  auto sensors = sensors::SensorManager::Instance()->GetSensors();
578  for (auto sensor : sensors)
579  {
580  if (sensor->Type() == "camera")
581  {
582  rendering::CameraPtr c = this->data->scene->GetCamera(
583  this->data->scene->StripSceneName(sensor->ScopedName()));
584 
585  if (c && std::find(this->data->cameras.begin(),
586  this->data->cameras.end(),
587  c->OgreCamera()) == this->data->cameras.end())
588  {
589  retVal.push_back(c);
590  }
591  }
592  }
593  return retVal;
594  }
595 
597 // Shader Params Wave Generation
598 
600  {
601  const std::string shaderType = "vertex";
602 
603  // Parameters (to load from SDF)
604  Ogre::Vector3 amplitude = Ogre::Vector3::ZERO;
605  Ogre::Vector3 wavenumber = Ogre::Vector3::ZERO;
606  Ogre::Vector3 omega = Ogre::Vector3::ZERO;
607  Ogre::Vector3 steepness = Ogre::Vector3::ZERO;
608  Ogre::Vector2 dir0 = Ogre::Vector2::ZERO;
609  Ogre::Vector2 dir1 = Ogre::Vector2::ZERO;
610  Ogre::Vector2 dir2 = Ogre::Vector2::ZERO;
611 
612  ToOgreVector3(this->data->waveParams->Amplitude_V(), amplitude);
613  ToOgreVector3(this->data->waveParams->Wavenumber_V(), wavenumber);
614  ToOgreVector3(this->data->waveParams->AngularFrequency_V(), omega);
615  ToOgreVector3(this->data->waveParams->Steepness_V(), steepness);
616  ToOgreVector2(this->data->waveParams->Direction_V(), dir0, dir1, dir2);
617 
618  // These parameters are updated on initialisation
619  auto& visual = *this->data->visual;
620 #if 0
621  visual.SetMaterialShaderParam(
622  "amplitude", shaderType, Ogre::StringConverter::toString(amplitude));
623  visual.SetMaterialShaderParam(
624  "wavenumber", shaderType, Ogre::StringConverter::toString(wavenumber));
625  visual.SetMaterialShaderParam(
626  "omega", shaderType, Ogre::StringConverter::toString(omega));
627  visual.SetMaterialShaderParam(
628  "steepness", shaderType, Ogre::StringConverter::toString(steepness));
629  visual.SetMaterialShaderParam(
630  "dir0", shaderType, Ogre::StringConverter::toString(dir0));
631  visual.SetMaterialShaderParam(
632  "dir1", shaderType, Ogre::StringConverter::toString(dir1));
633  visual.SetMaterialShaderParam(
634  "dir2", shaderType, Ogre::StringConverter::toString(dir2));
635 #else
637  "Nwaves", shaderType, std::to_string(this->data->waveParams->Number()));
639  "amplitude", shaderType, Ogre::StringConverter::toString(amplitude));
641  "wavenumber", shaderType, Ogre::StringConverter::toString(wavenumber));
643  "omega", shaderType, Ogre::StringConverter::toString(omega));
645  "steepness", shaderType, Ogre::StringConverter::toString(steepness));
647  "dir0", shaderType, Ogre::StringConverter::toString(dir0));
649  "dir1", shaderType, Ogre::StringConverter::toString(dir1));
651  "dir2", shaderType, Ogre::StringConverter::toString(dir2));
652  float tau = this->data->waveParams->Tau();
654  "tau", shaderType, Ogre::StringConverter::toString(tau));
655 #endif
656  }
657 
659 // OnCameraPreRender: How to update rtt before camera
660 
661  void WavefieldVisualPlugin::OnCameraPreRender(const std::string &_camera)
662  {
663  // Get appropriate camera source
664  rendering::CameraPtr camSource;
665  if (this->data->scene->UserCameraCount() > 0)
666  camSource = this->data->scene->GetUserCamera(0);
667  else
668  camSource = this->data->scene->GetCamera(_camera);
669 
670  // Update rtts first before updating camera
671  for (unsigned int i = 0; i < this->data->cameras.size(); ++i)
672  {
673  if (camSource->OgreCamera() == this->data->cameras.at(i))
674  {
675  this->data->reflectionRts.at(i)->update();
676  this->data->refractionRts.at(i)->update();
677  return;
678  }
679  }
680  }
681 
683 // pre and post RenderTargetUpdate(): RenderTargetListener methods
684 
686  const Ogre::RenderTargetEvent& rte)
687  {
688  // Hide ocean for creating reflection/refraction textures
689  if (this->data->oceanEntity)
690  {
691  this->data->oceanEntity->setVisible(false);
692  }
693 
694  // Reflection: hide entities below, reflect, and set the right frame
695  for (unsigned int i = 0; i < this->data->reflectionRts.size(); ++i)
696  {
697  Ogre::RenderTarget* rt = this->data->reflectionRts.at(i);
698  if (rte.source == rt)
699  {
700  this->data->cameras.at(i)->enableReflection(this->data->planeUp);
701  this->data->cameras.at(i)->enableCustomNearClipPlane(this->data->
702  planeUp);
703  this->data->reflectTex->setCurrentFrame(i);
704  return;
705  }
706  }
707 
708  // Refraction: hide entities above and set the right frame
709  for (unsigned int i = 0; i < this->data->refractionRts.size(); ++i)
710  {
711  Ogre::RenderTarget* rt = this->data->refractionRts.at(i);
712  if (rte.source == rt)
713  {
714  this->data->cameras.at(i)->enableCustomNearClipPlane(this->data->
715  planeDown);
716  this->data->refractTex->setCurrentFrame(i);
717  return;
718  }
719  }
720  }
721 
723  const Ogre::RenderTargetEvent& rte)
724  {
725  // Show ocean after creating reflection/refraction textures
726  if (this->data->oceanEntity)
727  {
728  this->data->oceanEntity->setVisible(true);
729  }
730 
731  // Reflection: reshow all entities
732  for (unsigned int i = 0; i < this->data->reflectionRts.size(); ++i)
733  {
734  Ogre::RenderTarget* rt = this->data->reflectionRts.at(i);
735  if (rte.source == rt)
736  {
737  this->data->cameras.at(i)->disableReflection();
738  this->data->cameras.at(i)->disableCustomNearClipPlane();
739  return;
740  }
741  }
742 
743  // Refraction: reshow all entities
744  for (unsigned int i = 0; i < this->data->refractionRts.size(); ++i)
745  {
746  Ogre::RenderTarget* rt = this->data->refractionRts.at(i);
747  if (rte.source == rt)
748  {
749  this->data->cameras.at(i)->disableCustomNearClipPlane();
750  return;
751  }
752  }
753  }
754 }
std::shared_ptr< WaveParameters > waveParams
The wavefield parameters.
void OnCameraPreRender(const std::string &_camera)
Update rtts before cameras.
void CreateRtts(Ogre::Camera *_camera)
Create reflection refraction rtts for a given camera Stores the render target and given camera...
void AddNewCamerasForReflectionRefraction()
Check for new cameras, setup rtts for them.
This file defines utilities for extracting parameters from SDF.
void ToOgreVector3(const std::vector< double > &_v, Ogre::Vector3 &_vout)
Convert a vector containing three doubles to an Ogre Vector3.
void SetShaderParams()
Update the vertex shader parameters.
std::string getName(void *handle)
std::string visualName
The visual&#39;s name.
std::shared_ptr< WavefieldVisualPluginPrivate > data
static bool SdfParamBool(sdf::Element &_sdf, const std::string &_paramName, const bool _defaultVal)
Extract a named bool parameter from an SDF element.
Definition: Utilities.cc:57
A class to manage the parameters for generating a wave.
Definition: Wavefield.hh:58
std::vector< Ogre::RenderTarget * > reflectionRts
static double SdfParamDouble(sdf::Element &_sdf, const std::string &_paramName, const double _defaultVal)
Extract a named double parameter from an SDF element.
Definition: Utilities.cc:69
sdf::ElementPtr sdf
The wavefield visual plugin SDF.
std::vector< Ogre::Camera * > cameras
virtual void preRenderTargetUpdate(const Ogre::RenderTargetEvent &rte)
Hide/Show objects for reflection/refraction render eg. hide objects above water for refraction hide o...
event::ConnectionPtr preRenderConnection
Event based connections.
Support for methods not available in legacy versions of Gazebo.
void UpdateClipPlanes()
Move and rotate clip planes to match ocean pose.
void ToOgreVector2(const std::vector< ignition::math::Vector2d > &_v, Ogre::Vector2 &_vout0, Ogre::Vector2 &_vout1, Ogre::Vector2 &_vout2)
rendering::VisualPtr visual
The visual containing this plugin.
virtual void Init()
Initialize the plugin.
virtual void Reset()
Reset the plugin.
Definition: Geometry.hh:28
void ToOgreVector3(const std::vector< ignition::math::Vector3d > &_v, Ogre::Vector3 &_vout0, Ogre::Vector3 &_vout1, Ogre::Vector3 &_vout2)
void SetMaterialShaderParam(Visual &_visual, const std::string &_paramName, const std::string &_shaderType, const std::string &_value)
Set a shader program parameter associated to this visual&#39;s material.
Definition: Gazebo.cc:33
std::vector< gazebo::rendering::CameraPtr > NewCameras()
Get new cameras not already contained in this->data->cameras.
void SetupReflectionRefraction()
Setup Ogre objects for reflection/refraction.
This file contains definitions for classes used to manage a wave field. This includes wave parameters...
This file defines a Gazebo VisualPlugin used to render a wave field and keep it synchronised with the...
virtual void postRenderTargetUpdate(const Ogre::RenderTargetEvent &rte)
virtual void Load(gazebo::rendering::VisualPtr _visual, sdf::ElementPtr _sdf)
Load the plugin.
void ToOgreVector2(const std::vector< double > &_v, Ogre::Vector2 &_vout)
Convert a vector containing two doubles to an Ogre Vector2.
void OnPreRender()
Called every PreRender event.
std::vector< Ogre::RenderTarget * > refractionRts


wave_gazebo_plugins
Author(s): Rhys Mainwaring
autogenerated on Thu May 7 2020 03:54:44