Gazebo Rendering

API Reference

8.2.0
BaseCamera.hh
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2015 Open Source Robotics Foundation
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 #ifndef GZ_RENDERING_BASE_BASECAMERA_HH_
18 #define GZ_RENDERING_BASE_BASECAMERA_HH_
19 
20 #include <string>
21 
22 #include <gz/math/Matrix3.hh>
23 #include <gz/math/Pose3.hh>
24 
25 #include <gz/common/Event.hh>
26 #include <gz/common/Console.hh>
27 #include <gz/utils/SuppressWarning.hh>
28 
29 #include "gz/rendering/Camera.hh"
30 #include "gz/rendering/Image.hh"
32 #include "gz/rendering/Scene.hh"
34 
35 namespace gz
36 {
37  namespace rendering
38  {
39  inline namespace GZ_RENDERING_VERSION_NAMESPACE {
40  template <class T>
41  class BaseDepthCamera;
42 
43  template <class T>
44  class BaseCamera :
45  public virtual Camera,
46  public virtual T
47  {
48  protected: BaseCamera();
49 
50  public: virtual ~BaseCamera();
51 
52  public: virtual unsigned int ImageWidth() const override;
53 
54  public: virtual void SetImageWidth(const unsigned int _width) override;
55 
56  public: virtual unsigned int ImageHeight() const override;
57 
58  public: virtual void SetImageHeight(const unsigned int _height) override;
59 
60  public: virtual PixelFormat ImageFormat() const override;
61 
62  public: virtual unsigned int ImageMemorySize() const override;
63 
64  public: virtual void SetImageFormat(PixelFormat _format,
65  bool _reinterpretable = false)
66  override;
67 
68  public: virtual math::Angle HFOV() const override;
69 
70  public: virtual void SetHFOV(const math::Angle &_hfov) override;
71 
72  public: virtual double AspectRatio() const override;
73 
74  public: virtual void SetAspectRatio(const double _ratio) override;
75 
76  public: virtual unsigned int AntiAliasing() const override;
77 
78  public: virtual void SetAntiAliasing(const unsigned int _aa) override;
79 
80  public: virtual double FarClipPlane() const override;
81 
82  public: virtual void SetFarClipPlane(const double _far) override;
83 
84  public: virtual double NearClipPlane() const override;
85 
86  public: virtual void SetNearClipPlane(const double _near) override;
87 
88  // Documentation inherited.
89  public: virtual void PreRender() override;
90 
91  // Documentation inherited.
92  public: virtual void PostRender() override;
93 
94  public: virtual void Update() override;
95 
96  public: virtual Image CreateImage() const override;
97 
98  public: virtual void Capture(Image &_image) override;
99 
100  public: virtual void Copy(Image &_image) const override;
101 
102  public: virtual bool SaveFrame(const std::string &_name) override;
103 
105  Camera::NewFrameListener _listener) override;
106 
107  public: virtual RenderWindowPtr CreateRenderWindow() override;
108 
109  // Documentation inherited.
110  public: virtual VisualPtr VisualAt(const gz::math::Vector2i
111  &_mousePos) override;
112 
113  // Documentation inherited.
114  public: virtual math::Matrix4d ProjectionMatrix() const override;
115 
116  // Documentation inherited.
117  public: virtual math::Matrix4d ViewMatrix() const override;
118 
119  // Documentation inherited.
120  public: virtual void SetProjectionMatrix(const math::Matrix4d &_matrix)
121  override;
122 
123  // Documentation inherited.
124  public: virtual CameraProjectionType ProjectionType() const override;
125 
126  // Documentation inherited.
127  public: virtual void SetProjectionType(
128  CameraProjectionType _type) override;
129 
130  // Documentation inherited.
131  public: virtual math::Vector2i Project(const math::Vector3d &_pt) const
132  override;
133 
134  // Documentation inherited.
135  // \sa Camera::SetMaterial(const MaterialPtr &) override;
136  public: virtual void SetMaterial(const MaterialPtr &_material)
137  override;
138 
139  // Documentation inherited.
140  public: virtual void SetTrackTarget(const NodePtr &_target,
141  const math::Vector3d &_offset,
142  const bool _worldFrame) override;
143 
144  // Documentation inherited.
145  public: virtual NodePtr TrackTarget() const override;
146 
147  // Documentation inherited.
148  public: virtual void SetTrackOffset(const math::Vector3d &_offset)
149  override;
150 
151  // Documentation inherited.
152  public: virtual math::Vector3d TrackOffset() const override;
153 
154  // Documentation inherited.
155  public: virtual void SetTrackPGain(const double _pGain) override;
156 
157  // Documentation inherited.
158  public: virtual double TrackPGain() const override;
159 
160  // Documentation inherited.
161  public: virtual void SetFollowTarget(const NodePtr &_target,
162  const math::Vector3d &_Offset, const bool _worldFrame)
163  override;
164 
165  // Documentation inherited.
166  public: virtual NodePtr FollowTarget() const override;
167 
168  // Documentation inherited.
169  public: virtual void SetFollowOffset(const math::Vector3d &_offset)
170  override;
171 
172  // Documentation inherited.
173  public: virtual math::Vector3d FollowOffset() const override;
174 
175  // Documentation inherited.
176  public: virtual void SetFollowPGain(const double _pGain) override;
177 
178  // Documentation inherited.
179  public: virtual double FollowPGain() const override;
180 
181  // Documentation inherited.
182  public: virtual unsigned int RenderTextureGLId() const override;
183 
184  // Documentation inherited.
185  public: virtual void RenderTextureMetalId(void *_textureIdPtr)
186  const override;
187 
188  // Documentation inherited.
189  public: virtual void PrepareForExternalSampling() override;
190 
191  // Documentation inherited.
192  public: virtual void AddRenderPass(const RenderPassPtr &_pass) override;
193 
194  // Documentation inherited.
195  public: virtual void RemoveRenderPass(const RenderPassPtr &_pass)
196  override;
197 
198  // Documentation inherited.
199  public: void RemoveAllRenderPasses() override;
200 
201  // Documentation inherited.
202  public: virtual unsigned int RenderPassCount() const override;
203 
204  // Documentation inherited.
205  public: virtual RenderPassPtr RenderPassByIndex(unsigned int _index)
206  const override;
207 
208  // Documentation inherited.
209  public: virtual void SetShadowsDirty() override;
210 
211  protected: virtual void *CreateImageBuffer() const;
212 
213  protected: virtual void Load() override;
214 
215  protected: virtual void Reset();
216 
217  protected: virtual RenderTargetPtr RenderTarget() const = 0;
218 
219  GZ_UTILS_WARN_IGNORE__DLL_INTERFACE_MISSING
220  protected: common::EventT<void(const void *, unsigned int, unsigned int,
221  unsigned int, const std::string &)> newFrameEvent;
222 
223  protected: ImagePtr imageBuffer;
224 
226  protected: double nearClip = 0.01;
227 
229  protected: double farClip = 1000.0;
230 
232  protected: double aspect = 1.3333333;
233 
235  protected: math::Angle hfov;
236 
238  protected: unsigned int antiAliasing = 0u;
239 
241  protected: NodePtr trackNode;
242 
244  protected: bool trackWorldFrame = false;
245 
249 
252  protected: double trackPGain = 1.0;
253 
255  protected: NodePtr followNode;
256  GZ_UTILS_WARN_RESUME__DLL_INTERFACE_MISSING
257 
259  protected: bool followWorldFrame = false;
260 
263  protected: double followPGain = 1.0;
264 
267 
270 
272  protected: CameraProjectionType projectionType = CPT_PERSPECTIVE;
273 
274  friend class BaseDepthCamera<T>;
275  };
276 
278  template <class T>
280  {
281  }
282 
284  template <class T>
286  {
287  }
288 
290  template <class T>
291  unsigned int BaseCamera<T>::ImageWidth() const
292  {
293  return this->RenderTarget()->Width();
294  }
295 
297  template <class T>
298  void BaseCamera<T>::SetImageWidth(const unsigned int _width)
299  {
300  this->RenderTarget()->SetWidth(_width);
301  this->SetAspectRatio(
302  static_cast<double>(_width) / static_cast<double>(this->ImageHeight()));
303  }
304 
306  template <class T>
307  unsigned int BaseCamera<T>::ImageHeight() const
308  {
309  return this->RenderTarget()->Height();
310  }
311 
313  template <class T>
314  void BaseCamera<T>::SetImageHeight(const unsigned int _height)
315  {
316  this->RenderTarget()->SetHeight(_height);
317  this->SetAspectRatio(
318  static_cast<double>(this->ImageWidth()) / static_cast<double>(_height));
319  }
320 
322  template <class T>
323  unsigned int BaseCamera<T>::ImageMemorySize() const
324  {
325  PixelFormat format = this->ImageFormat();
326  unsigned int width = this->ImageWidth();
327  unsigned int height = this->ImageHeight();
328  return PixelUtil::MemorySize(format, width, height);
329  }
330 
332  template <class T>
334  {
335  return this->RenderTarget()->Format();
336  }
337 
339  template <class T>
341  bool _reinterpretable)
342  {
343  this->RenderTarget()->SetFormat(_format, _reinterpretable);
344  }
345 
347  template <class T>
349  {
350  T::PreRender();
351 
352  {
353  CameraPtr camera =
354  std::dynamic_pointer_cast<Camera>(this->shared_from_this());
355  this->RenderTarget()->PreRender(camera);
356  }
357 
358  // camera following
359  if (this->followNode)
360  {
361  // tether camera fixed in world frame
362  if (this->followWorldFrame)
363  {
364  math::Vector3d targetCamPos =
365  this->followNode->WorldPosition() + this->followOffset;
366  math::Vector3d pos = this->WorldPosition() +
367  (targetCamPos - this->WorldPosition()) * this->followPGain;
368  this->SetWorldPosition(pos);
369  }
370  // tether camera fixed in target's local frame
371  else
372  {
373  math::Pose3d targetCamPose = math::Pose3d(this->followOffset,
374  this->WorldRotation());
375  targetCamPose = this->followNode->WorldPose() * targetCamPose;
376 
377  math::Vector3d pos = this->WorldPosition() +
378  (targetCamPose.Pos() - this->WorldPosition()) * this->followPGain;
379  this->SetWorldPosition(pos);
380  }
381  }
382 
383  // camera tracking
384  if (this->trackNode)
385  {
386  math::Vector3d eye = this->WorldPosition();
387  math::Pose3d targetPose = math::Pose3d(this->trackOffset,
389  if (this->trackWorldFrame)
390  {
391  targetPose.Pos() += this->trackNode->WorldPosition();
392  }
393  else
394  {
395  targetPose = this->trackNode->WorldPose() * targetPose;
396  }
397 
398  math::Pose3d p =
399  math::Matrix4d::LookAt(eye, targetPose.Pos()).Pose();
400 
401  math::Quaterniond q = p.Rot();
402  // skip slerp if we don't need it
403  if (!math::equal(this->trackPGain, 1.0))
404  {
406  this->trackPGain, this->WorldRotation(), p.Rot(), true);
407  }
408  this->SetWorldRotation(q);
409  }
410  }
411 
413  template <class T>
415  {
416  this->RenderTarget()->PostRender();
417  }
418 
420  template <class T>
422  {
423  PixelFormat format = this->ImageFormat();
424  unsigned int width = this->ImageWidth();
425  unsigned int height = this->ImageHeight();
426  return Image(width, height, format);
427  }
428 
430  template <class T>
432  {
433  this->Scene()->PreRender();
434  this->Render();
435  this->PostRender();
436  if (!this->Scene()->LegacyAutoGpuFlush())
437  {
438  this->Scene()->PostRender();
439  }
440  }
441 
443  template <class T>
445  {
446  this->Update();
447  this->Copy(_image);
448  }
449 
451  template <class T>
452  void BaseCamera<T>::Copy(Image &_image) const
453  {
454  this->RenderTarget()->Copy(_image);
455  }
456 
458  template <class T>
459  bool BaseCamera<T>::SaveFrame(const std::string &/*_name*/)
460  {
461  return false;
462  }
463 
465  template <class T>
467  Camera::NewFrameListener _listener)
468  {
469  return newFrameEvent.Connect(_listener);
470  }
471 
473  template <class T>
475  {
476  // TODO(anyone): determine proper type
477  unsigned int size = this->ImageMemorySize();
478  return new unsigned char *[size];
479  }
480 
482  template <class T>
484  {
485  T::Load();
486  }
487 
489  template <class T>
491  {
492  math::Angle fov;
493  fov.SetDegree(60);
494  this->SetImageWidth(1);
495  this->SetImageHeight(1);
496  this->SetImageFormat(PF_R8G8B8);
497  this->SetAspectRatio(0.0);
498  this->SetAntiAliasing(0u);
499  this->SetHFOV(fov);
500  this->SetNearClipPlane(0.01);
501  this->SetFarClipPlane(1000);
502  }
503 
505  template <class T>
507  {
508  // Does nothing by default
509  gzerr << "Render window not supported for render engine: " <<
510  this->Scene()->Engine()->Name() << std::endl;
511  return RenderWindowPtr();
512  }
513 
515  template <class T>
517  {
518  math::Matrix4d result = this->projectionMatrix;
519  if (this->projectionType == CPT_PERSPECTIVE)
520  {
521  double ratio = this->AspectRatio();
522  double fov = this->HFOV().Radian();
523  double vfov = 2.0 * std::atan(std::tan(fov / 2.0) / ratio);
524  double f = 1.0;
525  double _near = this->NearClipPlane();
526  double _far = this->FarClipPlane();
527  double top = _near * std::tan(0.5*vfov) / f;
528  double height = 2 * top;
529  double width = ratio * height;
530  double left = -0.5 * width;
531  double right = left + width;
532  double bottom = top - height;
533 
534  double invw = 1.0 / (right - left);
535  double invh = 1.0 / (top - bottom);
536  double invd = 1.0 / (_far - _near);
537  double x = 2 * _near * invw;
538  double y = 2 * _near * invh;
539  double a = (right + left) * invw;
540  double b = (top + bottom) * invh;
541  double c = -(_far + _near) * invd;
542  double d = -2 * _far * _near * invd;
543  result(0, 0) = x;
544  result(0, 2) = a;
545  result(1, 1) = y;
546  result(1, 2) = b;
547  result(2, 2) = c;
548  result(2, 3) = d;
549  result(3, 2) = -1;
550  }
551  else if (this->projectionType == CPT_ORTHOGRAPHIC)
552  {
553  double width = this->ImageWidth();
554  double height = this->ImageHeight();
555  double left = -width * 0.5;
556  double right = -left;
557  double top = height * 0.5;
558  double bottom = -top;
559  double _near = this->NearClipPlane();
560  double _far = this->FarClipPlane();
561 
562  double invw = 1.0 / (right - left);
563  double invh = 1.0 / (top - bottom);
564  double invd = 1.0 / (_far - _near);
565 
566  result(0, 0) = 2.0 * invw;
567  result(0, 3) = -(right + left) * invw;
568  result(1, 1) = 2.0 * invh;
569  result(1, 3) = -(top + bottom) * invh;
570  result(2, 2) = -2.0 * invd;
571  result(2, 3) = -(_far + _near) * invd;
572  result(3, 3) = 1.0;
573  }
574  else
575  {
576  gzerr << "Unknown camera projection type: " << this->projectionType
577  << std::endl;
578  }
579 
580  return result;
581  }
582 
584  template <class T>
586  {
587  this->projectionMatrix = _matrix;
588  }
589 
591  template <class T>
593  {
594  math::Matrix3d r(this->WorldPose().Rot());
595  // transform from y up to z up
596  math::Matrix3d tf(0, 0, -1,
597  -1, 0, 0,
598  0, 1, 0);
599  r = r * tf;
600  r.Transpose();
601  math::Vector3d t = r * this->WorldPose().Pos() * -1;
602  math::Matrix4d result;
603  result = r;
604  result.SetTranslation(t);
605  result(3, 3) = 1.0;
606  return result;
607  }
608 
610  template <class T>
612  {
613  this->projectionType = _type;
614  }
615 
617  template <class T>
619  {
620  return this->projectionType;
621  }
622 
624  template <class T>
626  {
627  math::Vector2i screenPos;
628  math::Matrix4d m = this->ProjectionMatrix() * this->ViewMatrix();
629  math::Vector3d pos = m * _pt;
630  double w = m(3, 0) * _pt.X() + m(3, 1) * _pt.Y() + m(3, 2) * _pt.Z()
631  + m(3, 3);
632  pos.X() = pos.X() / w;
633  pos.Y() = pos.Y() / w;
634 
635  screenPos.X() = static_cast<int>(
636  ((pos.X() / 2.0) + 0.5) * this->ImageWidth());
637  screenPos.Y() = static_cast<int>(
638  (1 - ((pos.Y() / 2.0) + 0.5)) * this->ImageHeight());
639  return screenPos;
640  }
641 
643  template <class T>
645  {
646  return this->hfov;
647  }
648 
650  template <class T>
652  &/*_mousePos*/)
653  {
654  gzerr << "VisualAt not implemented for the render engine" << std::endl;
655  return VisualPtr();
656  }
657 
659  template <class T>
661  {
662  this->hfov = _hfov;
663  }
664 
666  template <class T>
668  {
669  // Invalid AR values fallback to auto aspect ratio to maintain
670  // ABI compatibility.
671  // See https://github.com/gazebosim/gz-rendering/issues/763
672  if (this->aspect <= 0.0)
673  {
674  return static_cast<double>(this->ImageWidth()) /
675  static_cast<double>(this->ImageHeight());
676  }
677  return this->aspect;
678  }
679 
681  template <class T>
682  void BaseCamera<T>::SetAspectRatio(const double _aspect)
683  {
684  this->aspect = _aspect;
685  }
686 
688  template <class T>
689  unsigned int BaseCamera<T>::AntiAliasing() const
690  {
691  return this->antiAliasing;
692  }
693 
695  template <class T>
696  void BaseCamera<T>::SetAntiAliasing(const unsigned int _aa)
697  {
698  this->antiAliasing = _aa;
699  }
700 
702  template <class T>
704  {
705  return this->farClip;
706  }
707 
709  template <class T>
710  void BaseCamera<T>::SetFarClipPlane(const double _far)
711  {
712  this->farClip = _far;
713  }
714 
716  template <class T>
718  {
719  return this->nearClip;
720  }
721 
723  template <class T>
724  void BaseCamera<T>::SetNearClipPlane(const double _near)
725  {
726  this->nearClip = _near;
727  }
728 
730  template <class T>
732  const math::Vector3d &_offset, const bool _worldFrame)
733  {
734  this->trackNode = _target;
735  this->trackWorldFrame = _worldFrame;
736  this->trackOffset = _offset;
737  }
738 
740  template <class T>
742  {
743  return this->trackNode;
744  }
745 
747  template <class T>
749  {
750  return this->trackOffset;
751  }
752 
754  template <class T>
756  {
757  this->trackOffset = _offset;
758  }
759 
761  template <class T>
762  void BaseCamera<T>::SetTrackPGain(const double _pGain)
763  {
764  this->trackPGain = math::clamp(_pGain, 0.0, 1.0);
765  }
766 
768  template <class T>
770  {
771  return this->trackPGain;
772  }
773 
775  template <class T>
777  const math::Vector3d &_offset, const bool _worldFrame)
778  {
779  this->followNode = _target;
780  this->followWorldFrame = _worldFrame;
781  this->followOffset = _offset;
782  }
783 
785  template <class T>
787  {
788  return this->followNode;
789  }
790 
792  template <class T>
794  {
795  return this->followOffset;
796  }
797 
799  template <class T>
801  {
802  this->followOffset = _offset;
803  }
804 
806  template <class T>
807  void BaseCamera<T>::SetFollowPGain(const double _pGain)
808  {
809  this->followPGain = math::clamp(_pGain, 0.0, 1.0);
810  }
811 
813  template <class T>
815  {
816  return this->followPGain;
817  }
818 
820  template <class T>
821  void BaseCamera<T>::SetMaterial(const MaterialPtr &/*_material*/)
822  {
823  gzerr << "SetMaterial not implemented for current render"
824  << " engine" << std::endl;
825  }
826 
828  template <class T>
829  unsigned int BaseCamera<T>::RenderTextureGLId() const
830  {
831  gzerr << "RenderTextureGLId is not supported by current render"
832  << " engine" << std::endl;
833  return 0u;
834  }
835 
837  template <class T>
839  {
840  gzerr << "RenderTextureMetalId is not supported by current render"
841  << " engine" << std::endl;
842  }
843 
845  template <class T>
847  {
848  gzerr << "PrepareForExternalSampling is not supported by current render"
849  << " engine" << std::endl;
850  }
851 
853  template <class T>
855  {
856  this->RenderTarget()->AddRenderPass(_pass);
857  }
858 
860  template <class T>
862  {
863  this->RenderTarget()->RemoveRenderPass(_pass);
864  }
865 
867  template <class T>
869  {
870  RenderTargetPtr renderTarget = this->RenderTarget();
871  if (renderTarget)
872  {
873  renderTarget->RemoveAllRenderPasses();
874  }
875  }
876 
878  template <class T>
879  unsigned int BaseCamera<T>::RenderPassCount() const
880  {
881  return this->RenderTarget()->RenderPassCount();
882  }
883 
885  template <class T>
887  {
888  return this->RenderTarget()->RenderPassByIndex(_index);
889  }
890 
892  template <class T>
894  {
895  // no op
896  }
897  }
898  }
899 }
900 #endif