Gazebo Rendering

API Reference

6.6.3
gz/rendering/base/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/common/SuppressWarning.hh>
28 
29 #include "gz/rendering/Camera.hh"
30 #include "gz/rendering/Image.hh"
32 #include "gz/rendering/Scene.hh"
34 
35 namespace ignition
36 {
37  namespace rendering
38  {
39  inline namespace IGNITION_RENDERING_VERSION_NAMESPACE {
40  template <class T>
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) override;
65 
66  public: virtual math::Angle HFOV() const override;
67 
68  public: virtual void SetHFOV(const math::Angle &_hfov) override;
69 
70  public: virtual double AspectRatio() const override;
71 
72  public: virtual void SetAspectRatio(const double _ratio) override;
73 
74  public: virtual unsigned int AntiAliasing() const override;
75 
76  public: virtual void SetAntiAliasing(const unsigned int _aa) override;
77 
78  public: virtual double FarClipPlane() const override;
79 
80  public: virtual void SetFarClipPlane(const double _far) override;
81 
82  public: virtual double NearClipPlane() const override;
83 
84  public: virtual void SetNearClipPlane(const double _near) override;
85 
86  // Documentation inherited.
87  public: virtual void PreRender() override;
88 
89  // Documentation inherited.
90  public: virtual void PostRender() override;
91 
92  public: virtual void Update() override;
93 
94  public: virtual Image CreateImage() const override;
95 
96  public: virtual void Capture(Image &_image) override;
97 
98  public: virtual void Copy(Image &_image) const override;
99 
100  public: virtual bool SaveFrame(const std::string &_name) override;
101 
102  public: virtual common::ConnectionPtr ConnectNewImageFrame(
103  Camera::NewFrameListener _listener) override;
104 
105  public: virtual RenderWindowPtr CreateRenderWindow() override;
106 
107  // Documentation inherited.
108  public: virtual VisualPtr VisualAt(const gz::math::Vector2i
109  &_mousePos) override;
110 
111  // Documentation inherited.
112  public: virtual math::Matrix4d ProjectionMatrix() const override;
113 
114  // Documentation inherited.
115  public: virtual math::Matrix4d ViewMatrix() const override;
116 
117  // Documentation inherited.
118  public: virtual void SetProjectionMatrix(const math::Matrix4d &_matrix)
119  override;
120 
121  // Documentation inherited.
122  public: virtual CameraProjectionType ProjectionType() const override;
123 
124  // Documentation inherited.
125  public: virtual void SetProjectionType(
126  CameraProjectionType _type) override;
127 
128  // Documentation inherited.
129  public: virtual math::Vector2i Project(const math::Vector3d &_pt) const
130  override;
131 
132  // Documentation inherited.
133  // \sa Camera::SetMaterial(const MaterialPtr &) override;
134  public: virtual void SetMaterial(const MaterialPtr &_material)
135  override;
136 
137  // Documentation inherited.
138  public: virtual void SetTrackTarget(const NodePtr &_target,
139  const math::Vector3d &_offset,
140  const bool _worldFrame) override;
141 
142  // Documentation inherited.
143  public: virtual NodePtr TrackTarget() const override;
144 
145  // Documentation inherited.
146  public: virtual void SetTrackOffset(const math::Vector3d &_offset)
147  override;
148 
149  // Documentation inherited.
150  public: virtual math::Vector3d TrackOffset() const override;
151 
152  // Documentation inherited.
153  public: virtual void SetTrackPGain(const double _pGain) override;
154 
155  // Documentation inherited.
156  public: virtual double TrackPGain() const override;
157 
158  // Documentation inherited.
159  public: virtual void SetFollowTarget(const NodePtr &_target,
160  const math::Vector3d &_Offset, const bool _worldFrame)
161  override;
162 
163  // Documentation inherited.
164  public: virtual NodePtr FollowTarget() const override;
165 
166  // Documentation inherited.
167  public: virtual void SetFollowOffset(const math::Vector3d &_offset)
168  override;
169 
170  // Documentation inherited.
171  public: virtual math::Vector3d FollowOffset() const override;
172 
173  // Documentation inherited.
174  public: virtual void SetFollowPGain(const double _pGain) override;
175 
176  // Documentation inherited.
177  public: virtual double FollowPGain() const override;
178 
179  // Documentation inherited.
180  public: virtual unsigned int RenderTextureGLId() const override;
181 
182  // Documentation inherited.
183  public: virtual void AddRenderPass(const RenderPassPtr &_pass) override;
184 
185  // Documentation inherited.
186  public: virtual void RemoveRenderPass(const RenderPassPtr &_pass)
187  override;
188 
189  // Documentation inherited.
190  public: virtual unsigned int RenderPassCount() const override;
191 
192  // Documentation inherited.
193  public: virtual RenderPassPtr RenderPassByIndex(unsigned int _index)
194  const override;
195 
196  // Documentation inherited.
197  public: virtual void SetShadowsDirty() override;
198 
199  protected: virtual void *CreateImageBuffer() const;
200 
201  protected: virtual void Load() override;
202 
203  protected: virtual void Reset();
204 
205  protected: virtual RenderTargetPtr RenderTarget() const = 0;
206 
208  protected: common::EventT<void(const void *, unsigned int, unsigned int,
209  unsigned int, const std::string &)> newFrameEvent;
210 
211  protected: ImagePtr imageBuffer;
212 
214  protected: double nearClip = 0.01;
215 
217  protected: double farClip = 1000.0;
218 
220  protected: double aspect = 1.3333333;
221 
223  protected: math::Angle hfov;
224 
226  protected: unsigned int antiAliasing = 0u;
227 
229  protected: NodePtr trackNode;
230 
232  protected: bool trackWorldFrame = false;
233 
237 
240  protected: double trackPGain = 1.0;
241 
243  protected: NodePtr followNode;
245 
247  protected: bool followWorldFrame = false;
248 
251  protected: double followPGain = 1.0;
252 
255 
258 
260  protected: CameraProjectionType projectionType = CPT_PERSPECTIVE;
261 
262  friend class BaseDepthCamera<T>;
263  };
264 
266  template <class T>
268  {
269  }
270 
272  template <class T>
274  {
275  }
276 
278  template <class T>
279  unsigned int BaseCamera<T>::ImageWidth() const
280  {
281  return this->RenderTarget()->Width();
282  }
283 
285  template <class T>
286  void BaseCamera<T>::SetImageWidth(const unsigned int _width)
287  {
288  this->RenderTarget()->SetWidth(_width);
289  this->SetAspectRatio(
290  static_cast<double>(_width) / static_cast<double>(this->ImageHeight()));
291  }
292 
294  template <class T>
295  unsigned int BaseCamera<T>::ImageHeight() const
296  {
297  return this->RenderTarget()->Height();
298  }
299 
301  template <class T>
302  void BaseCamera<T>::SetImageHeight(const unsigned int _height)
303  {
304  this->RenderTarget()->SetHeight(_height);
305  this->SetAspectRatio(
306  static_cast<double>(this->ImageWidth()) / static_cast<double>(_height));
307  }
308 
310  template <class T>
311  unsigned int BaseCamera<T>::ImageMemorySize() const
312  {
313  PixelFormat format = this->ImageFormat();
314  unsigned int width = this->ImageWidth();
315  unsigned int height = this->ImageHeight();
316  return PixelUtil::MemorySize(format, width, height);
317  }
318 
320  template <class T>
322  {
323  return this->RenderTarget()->Format();
324  }
325 
327  template <class T>
329  {
330  this->RenderTarget()->SetFormat(_format);
331  }
332 
334  template <class T>
336  {
337  T::PreRender();
338 
339  this->RenderTarget()->PreRender();
340 
341  // camera following
342  if (this->followNode)
343  {
344  // tether camera fixed in world frame
345  if (this->followWorldFrame)
346  {
347  math::Vector3d targetCamPos =
348  this->followNode->WorldPosition() + this->followOffset;
349  math::Vector3d pos = this->WorldPosition() +
350  (targetCamPos - this->WorldPosition()) * this->followPGain;
351  this->SetWorldPosition(pos);
352  }
353  // tether camera fixed in target's local frame
354  else
355  {
356  math::Pose3d targetCamPose = math::Pose3d(this->followOffset,
357  this->WorldRotation());
358  targetCamPose = this->followNode->WorldPose() * targetCamPose;
359 
360  math::Vector3d pos = this->WorldPosition() +
361  (targetCamPose.Pos() - this->WorldPosition()) * this->followPGain;
362  this->SetWorldPosition(pos);
363  }
364  }
365 
366  // camera tracking
367  if (this->trackNode)
368  {
369  math::Vector3d eye = this->WorldPosition();
370  math::Pose3d targetPose = math::Pose3d(this->trackOffset,
372  if (this->trackWorldFrame)
373  {
374  targetPose.Pos() += this->trackNode->WorldPosition();
375  }
376  else
377  {
378  targetPose = this->trackNode->WorldPose() * targetPose;
379  }
380 
381  math::Pose3d p =
382  math::Matrix4d::LookAt(eye, targetPose.Pos()).Pose();
383 
384  math::Quaterniond q = p.Rot();
385  // skip slerp if we don't need it
386  if (!math::equal(this->trackPGain, 1.0))
387  {
389  this->trackPGain, this->WorldRotation(), p.Rot(), true);
390  }
391  this->SetWorldRotation(q);
392  }
393  }
394 
396  template <class T>
398  {
399  this->RenderTarget()->PostRender();
400  }
401 
403  template <class T>
405  {
406  PixelFormat format = this->ImageFormat();
407  unsigned int width = this->ImageWidth();
408  unsigned int height = this->ImageHeight();
409  return Image(width, height, format);
410  }
411 
413  template <class T>
415  {
416  this->Scene()->PreRender();
417  this->Render();
418  this->PostRender();
419  if (!this->Scene()->LegacyAutoGpuFlush())
420  {
421  this->Scene()->PostRender();
422  }
423  }
424 
426  template <class T>
428  {
429  this->Update();
430  this->Copy(_image);
431  }
432 
434  template <class T>
435  void BaseCamera<T>::Copy(Image &_image) const
436  {
437  this->RenderTarget()->Copy(_image);
438  }
439 
441  template <class T>
442  bool BaseCamera<T>::SaveFrame(const std::string &/*_name*/)
443  {
444  return false;
445  }
446 
448  template <class T>
450  Camera::NewFrameListener _listener)
451  {
452  return newFrameEvent.Connect(_listener);
453  }
454 
456  template <class T>
458  {
459  // TODO(anyone): determine proper type
460  unsigned int size = this->ImageMemorySize();
461  return new unsigned char *[size];
462  }
463 
465  template <class T>
467  {
468  T::Load();
469  }
470 
472  template <class T>
474  {
475  math::Angle fov;
476  fov.Degree(60);
477  this->SetImageWidth(1);
478  this->SetImageHeight(1);
479  this->SetImageFormat(PF_R8G8B8);
480  this->SetAspectRatio(1.33333);
481  this->SetAntiAliasing(0u);
482  this->SetHFOV(fov);
483  this->SetNearClipPlane(0.01);
484  this->SetFarClipPlane(1000);
485  }
486 
488  template <class T>
490  {
491  // Does nothing by default
492  ignerr << "Render window not supported for render engine: " <<
493  this->Scene()->Engine()->Name() << std::endl;
494  return RenderWindowPtr();
495  }
496 
498  template <class T>
500  {
501  math::Matrix4d result = this->projectionMatrix;
502  if (this->projectionType == CPT_PERSPECTIVE)
503  {
504  double ratio = this->AspectRatio();
505  double fov = this->HFOV().Radian();
506  double vfov = 2.0 * std::atan(std::tan(fov / 2.0) / ratio);
507  double f = 1.0;
508  double _near = this->NearClipPlane();
509  double _far = this->FarClipPlane();
510  double top = _near * std::tan(0.5*vfov) / f;
511  double height = 2 * top;
512  double width = ratio * height;
513  double left = -0.5 * width;
514  double right = left + width;
515  double bottom = top - height;
516 
517  double invw = 1.0 / (right - left);
518  double invh = 1.0 / (top - bottom);
519  double invd = 1.0 / (_far - _near);
520  double x = 2 * _near * invw;
521  double y = 2 * _near * invh;
522  double a = (right + left) * invw;
523  double b = (top + bottom) * invh;
524  double c = -(_far + _near) * invd;
525  double d = -2 * _far * _near * invd;
526  result(0, 0) = x;
527  result(0, 2) = a;
528  result(1, 1) = y;
529  result(1, 2) = b;
530  result(2, 2) = c;
531  result(2, 3) = d;
532  result(3, 2) = -1;
533  }
534  else if (this->projectionType == CPT_ORTHOGRAPHIC)
535  {
536  double width = this->ImageWidth();
537  double height = this->ImageHeight();
538  double left = -width * 0.5;
539  double right = -left;
540  double top = height * 0.5;
541  double bottom = -top;
542  double _near = this->NearClipPlane();
543  double _far = this->FarClipPlane();
544 
545  double invw = 1.0 / (right - left);
546  double invh = 1.0 / (top - bottom);
547  double invd = 1.0 / (_far - _near);
548 
549  result(0, 0) = 2.0 * invw;
550  result(0, 3) = -(right + left) * invw;
551  result(1, 1) = 2.0 * invh;
552  result(1, 3) = -(top + bottom) * invh;
553  result(2, 2) = -2.0 * invd;
554  result(2, 3) = -(_far + _near) * invd;
555  result(3, 3) = 1.0;
556  }
557  else
558  {
559  ignerr << "Unknown camera projection type: " << this->projectionType
560  << std::endl;
561  }
562 
563  return result;
564  }
565 
567  template <class T>
569  {
570  this->projectionMatrix = _matrix;
571  }
572 
574  template <class T>
576  {
577  math::Matrix3d r(this->WorldPose().Rot());
578  // transform from y up to z up
579  math::Matrix3d tf(0, 0, -1,
580  -1, 0, 0,
581  0, 1, 0);
582  r = r * tf;
583  r.Transpose();
584  math::Vector3d t = r * this->WorldPose().Pos() * -1;
585  math::Matrix4d result;
586  result = r;
587  result.SetTranslation(t);
588  result(3, 3) = 1.0;
589  return result;
590  }
591 
593  template <class T>
595  {
596  this->projectionType = _type;
597  }
598 
600  template <class T>
602  {
603  return this->projectionType;
604  }
605 
607  template <class T>
609  {
610  math::Vector2i screenPos;
611  math::Matrix4d m = this->ProjectionMatrix() * this->ViewMatrix();
612  math::Vector3d pos = m * _pt;
613  double w = m(3, 0) * _pt.X() + m(3, 1) * _pt.Y() + m(3, 2) * _pt.Z()
614  + m(3, 3);
615  pos.X() = pos.X() / w;
616  pos.Y() = pos.Y() / w;
617 
618  screenPos.X() = static_cast<int>(
619  ((pos.X() / 2.0) + 0.5) * this->ImageWidth());
620  screenPos.Y() = static_cast<int>(
621  (1 - ((pos.Y() / 2.0) + 0.5)) * this->ImageHeight());
622  return screenPos;
623  }
624 
626  template <class T>
628  {
629  return this->hfov;
630  }
631 
633  template <class T>
634  VisualPtr BaseCamera<T>::VisualAt(const gz::math::Vector2i
635  &/*_mousePos*/)
636  {
637  ignerr << "VisualAt not implemented for the render engine" << std::endl;
638  return VisualPtr();
639  }
640 
642  template <class T>
644  {
645  this->hfov = _hfov;
646  }
647 
649  template <class T>
651  {
652  return this->aspect;
653  }
654 
656  template <class T>
657  void BaseCamera<T>::SetAspectRatio(const double _aspect)
658  {
659  this->aspect = _aspect;
660  }
661 
663  template <class T>
664  unsigned int BaseCamera<T>::AntiAliasing() const
665  {
666  return this->antiAliasing;
667  }
668 
670  template <class T>
671  void BaseCamera<T>::SetAntiAliasing(const unsigned int _aa)
672  {
673  this->antiAliasing = _aa;
674  }
675 
677  template <class T>
679  {
680  return this->farClip;
681  }
682 
684  template <class T>
685  void BaseCamera<T>::SetFarClipPlane(const double _far)
686  {
687  this->farClip = _far;
688  }
689 
691  template <class T>
693  {
694  return this->nearClip;
695  }
696 
698  template <class T>
699  void BaseCamera<T>::SetNearClipPlane(const double _near)
700  {
701  this->nearClip = _near;
702  }
703 
705  template <class T>
707  const math::Vector3d &_offset, const bool _worldFrame)
708  {
709  this->trackNode = _target;
710  this->trackWorldFrame = _worldFrame;
711  this->trackOffset = _offset;
712  }
713 
715  template <class T>
717  {
718  return this->trackNode;
719  }
720 
722  template <class T>
724  {
725  return this->trackOffset;
726  }
727 
729  template <class T>
731  {
732  this->trackOffset = _offset;
733  }
734 
736  template <class T>
737  void BaseCamera<T>::SetTrackPGain(const double _pGain)
738  {
739  this->trackPGain = math::clamp(_pGain, 0.0, 1.0);
740  }
741 
743  template <class T>
745  {
746  return this->trackPGain;
747  }
748 
750  template <class T>
752  const math::Vector3d &_offset, const bool _worldFrame)
753  {
754  this->followNode = _target;
755  this->followWorldFrame = _worldFrame;
756  this->followOffset = _offset;
757  }
758 
760  template <class T>
762  {
763  return this->followNode;
764  }
765 
767  template <class T>
769  {
770  return this->followOffset;
771  }
772 
774  template <class T>
776  {
777  this->followOffset = _offset;
778  }
779 
781  template <class T>
782  void BaseCamera<T>::SetFollowPGain(const double _pGain)
783  {
784  this->followPGain = math::clamp(_pGain, 0.0, 1.0);
785  }
786 
788  template <class T>
790  {
791  return this->followPGain;
792  }
793 
795  template <class T>
796  void BaseCamera<T>::SetMaterial(const MaterialPtr &/*_material*/)
797  {
798  ignerr << "SetMaterial not implemented for current render"
799  << " engine" << std::endl;
800  }
801 
803  template <class T>
804  unsigned int BaseCamera<T>::RenderTextureGLId() const
805  {
806  ignerr << "RenderTextureGLId is not supported by current render"
807  << " engine" << std::endl;
808  return 0u;
809  }
810 
812  template <class T>
814  {
815  this->RenderTarget()->AddRenderPass(_pass);
816  }
817 
819  template <class T>
821  {
822  this->RenderTarget()->RemoveRenderPass(_pass);
823  }
824 
826  template <class T>
827  unsigned int BaseCamera<T>::RenderPassCount() const
828  {
829  return this->RenderTarget()->RenderPassCount();
830  }
831 
833  template <class T>
835  {
836  return this->RenderTarget()->RenderPassByIndex(_index);
837  }
838 
840  template <class T>
842  {
843  // no op
844  }
845  }
846  }
847 }
848 #endif
Definition: gz/rendering/base/BaseCamera.hh:41
T tan(T... args)
@ PF_R8G8B8
< RGB, 1-byte per channel
Definition: gz/rendering/PixelFormat.hh:39
STL class.
STL class.
virtual unsigned int RenderPassCount() const =0
Get the number of render passes applied to the render target.
#define IGN_COMMON_WARN_IGNORE__DLL_INTERFACE_MISSING
virtual RenderPassPtr RenderPassByIndex(unsigned int _index) const override
Get a render passes by index.
Definition: gz/rendering/base/BaseCamera.hh:834
double followPGain
P gain for follow mode. Determines how fast the camera moves to follow the target node....
Definition: gz/rendering/base/BaseCamera.hh:251
virtual unsigned int RenderTextureGLId() const override
Get the OpenGL texture id associated with the render texture used by this camera. A valid id is retur...
Definition: gz/rendering/base/BaseCamera.hh:804
bool equal(const T &_a, const T &_b, const T &_epsilon=T(1e-6))
static Matrix4< T > LookAt(const Vector3< T > &_eye, const Vector3< T > &_target, const Vector3< T > &_up=Vector3< T >::UnitZ)
virtual RenderTargetPtr RenderTarget() const =0
void SetTranslation(const Vector3< T > &_t)
math::Vector3d trackOffset
Set camera to track a point offset in target node's local or world frame depending on trackWorldFrame...
Definition: gz/rendering/base/BaseCamera.hh:236
virtual bool SaveFrame(const std::string &_name) override
Writes the previously rendered frame to a file. This function can be called multiple times after Post...
Definition: gz/rendering/base/BaseCamera.hh:442
PixelFormat
Image pixel format types.
Definition: gz/rendering/PixelFormat.hh:32
common::EventT< void(const void *, unsigned int, unsigned int, unsigned int, const std::string &)> newFrameEvent
Definition: gz/rendering/base/BaseCamera.hh:209
ImagePtr imageBuffer
Definition: gz/rendering/base/BaseCamera.hh:211
virtual void AddRenderPass(const RenderPassPtr &_pass)=0
Add a render pass to the render target.
virtual void * CreateImageBuffer() const
Definition: gz/rendering/base/BaseCamera.hh:457
virtual common::ConnectionPtr ConnectNewImageFrame(Camera::NewFrameListener _listener) override
Subscribes a new listener to this camera's new frame event.
Definition: gz/rendering/base/BaseCamera.hh:449
Vector3< T > & Pos()
virtual void SetFollowTarget(const NodePtr &_target, const math::Vector3d &_Offset, const bool _worldFrame) override
Set a node for camera to follow. The camera will automatically update its position to keep itself at ...
Definition: gz/rendering/base/BaseCamera.hh:751
static unsigned int MemorySize(PixelFormat _format, unsigned int _width, unsigned int _height)
Get total memory size in bytes for an image with the given format and dimensions. If an invalid forma...
virtual RenderWindowPtr CreateRenderWindow() override
Create a render window.
Definition: gz/rendering/base/BaseCamera.hh:489
double trackPGain
P gain for tracking. Determines how fast the camera rotates to look at the target node....
Definition: gz/rendering/base/BaseCamera.hh:240
virtual void SetImageFormat(PixelFormat _format) override
Set the image pixel format.
Definition: gz/rendering/base/BaseCamera.hh:328
virtual std::string Name() const =0
Get name of the render-engine.
virtual math::Matrix4d ProjectionMatrix() const override
Get the projection matrix for this camera.
Definition: gz/rendering/base/BaseCamera.hh:499
virtual RenderEngine * Engine() const =0
Get the creating render-engine of the scene.
Encapsulates a raw image buffer and relevant properties.
Definition: gz/rendering/Image.hh:36
virtual void SetAntiAliasing(const unsigned int _aa) override
Set the level of anti-aliasing used during rendering. If a value of 0 is given, no anti-aliasing will...
Definition: gz/rendering/base/BaseCamera.hh:671
virtual unsigned int Width() const =0
Get render target width in pixels.
virtual void SetImageHeight(const unsigned int _height) override
Set the image height in pixels.
Definition: gz/rendering/base/BaseCamera.hh:302
BaseCamera()
Definition: gz/rendering/base/BaseCamera.hh:267
virtual void SetTrackPGain(const double _pGain) override
Set track P Gain. Determines how fast the camera rotates to look at the target node....
Definition: gz/rendering/base/BaseCamera.hh:737
virtual ~BaseCamera()
Definition: gz/rendering/base/BaseCamera.hh:273
virtual unsigned int Height() const =0
Get render target height in pixels.
double nearClip
Near clipping plane distance.
Definition: gz/rendering/base/BaseCamera.hh:214
virtual void PostRender()=0
Post process this object and any of its children after rendering.
virtual double FarClipPlane() const override
Get the camera's far clipping plane distance.
Definition: gz/rendering/base/BaseCamera.hh:678
static const Quaternion Identity
Posable camera used for rendering the scene graph.
Definition: gz/rendering/Camera.hh:49
virtual void Copy(Image &_image) const =0
Write rendered image to given Image. The RenderTarget will convert the underlying image to the specif...
CameraProjectionType
Enum for projection types.
Definition: gz/rendering/Camera.hh:39
static Quaternion< T > Slerp(T _fT, const Quaternion< T > &_rkP, const Quaternion< T > &_rkQ, bool _shortestPath=false)
double aspect
Aspect ratio.
Definition: gz/rendering/base/BaseCamera.hh:220
virtual math::Vector3d TrackOffset() const override
Get the track offset vector in the frame specified at the time the track target is set.
Definition: gz/rendering/base/BaseCamera.hh:723
virtual void Capture(Image &_image) override
Renders a new frame and writes the results to the given image. This is a convenience function for sin...
Definition: gz/rendering/base/BaseCamera.hh:427
#define ignerr
Pose3< double > Pose3d
math::Vector3d followOffset
Offset distance between camera and target node being followed.
Definition: gz/rendering/base/BaseCamera.hh:254
Manages a single scene-graph. This class updates scene-wide properties and holds the root scene node....
Definition: gz/rendering/Scene.hh:49
virtual void SetImageWidth(const unsigned int _width) override
Set the image width in pixels.
Definition: gz/rendering/base/BaseCamera.hh:286
virtual NodePtr TrackTarget() const override
Get the target node being tracked.
Definition: gz/rendering/base/BaseCamera.hh:716
virtual void RemoveRenderPass(const RenderPassPtr &_pass) override
Remove a render pass from the camera.
Definition: gz/rendering/base/BaseCamera.hh:820
virtual unsigned int AntiAliasing() const override
Get the level of anti-aliasing used during rendering.
Definition: gz/rendering/base/BaseCamera.hh:664
virtual unsigned int ImageWidth() const override
Get the image width in pixels.
Definition: gz/rendering/base/BaseCamera.hh:279
virtual void SetHFOV(const math::Angle &_hfov) override
Set the camera's horizontal field-of-view.
Definition: gz/rendering/base/BaseCamera.hh:643
virtual RenderPassPtr RenderPassByIndex(unsigned int _index) const =0
Get a render pass by index.
@ CPT_PERSPECTIVE
Perspective projection.
Definition: gz/rendering/Camera.hh:42
CameraProjectionType projectionType
Camera projection type.
Definition: gz/rendering/base/BaseCamera.hh:260
virtual void PreRender()=0
Prepare this object and any of its children for rendering. This should be called for each object in a...
virtual double NearClipPlane() const override
Get the camera's near clipping plane distance.
Definition: gz/rendering/base/BaseCamera.hh:692
virtual void SetMaterial(const MaterialPtr &_material) override
Set a material that the camera should see on all objects.
Definition: gz/rendering/base/BaseCamera.hh:796
virtual void PreRender()=0
Prepare scene for rendering. The scene will flushing any scene changes by traversing scene-graph,...
virtual double FollowPGain() const override
Get the camera follow movement P gain.
Definition: gz/rendering/base/BaseCamera.hh:789
Represents a render-target to which cameras can render images.
Definition: gz/rendering/RenderTarget.hh:37
virtual unsigned int RenderPassCount() const override
Get the number of render passes applied to the camera.
Definition: gz/rendering/base/BaseCamera.hh:827
T clamp(T _v, T _min, T _max)
T atan(T... args)
virtual void Reset()
Definition: gz/rendering/base/BaseCamera.hh:473
virtual void Load() override
Definition: gz/rendering/base/BaseCamera.hh:466
virtual void PreRender() override
Prepare this object and any of its children for rendering. This should be called for each object in a...
Definition: gz/rendering/base/BaseCamera.hh:335
bool followWorldFrame
Follow target in world frame.
Definition: gz/rendering/base/BaseCamera.hh:247
double Degree() const
virtual math::Vector3d FollowOffset() const override
Get the follow offset vector in the frame specified at the time the follow target is set.
Definition: gz/rendering/base/BaseCamera.hh:768
virtual math::Matrix4d ViewMatrix() const override
Get the view matrix for this camera.
Definition: gz/rendering/base/BaseCamera.hh:575
virtual void Copy(Image &_image) const override
Writes the last rendered image to the given image buffer. This function can be called multiple times ...
Definition: gz/rendering/base/BaseCamera.hh:435
NodePtr followNode
Target node to follow.
Definition: gz/rendering/base/BaseCamera.hh:243
virtual void SetProjectionType(CameraProjectionType _type) override
Set the projection type for this camera This changes the projection matrix of the camera based on the...
Definition: gz/rendering/base/BaseCamera.hh:594
virtual void SetAspectRatio(const double _ratio) override
Set the camera's aspect ratio. This value determines the cameras vertical field-of-view....
Definition: gz/rendering/base/BaseCamera.hh:657
virtual void SetProjectionMatrix(const math::Matrix4d &_matrix) override
Set the projection matrix for this camera. This overrides the standard projection matrix computed bas...
Definition: gz/rendering/base/BaseCamera.hh:568
shared_ptr< Visual > VisualPtr
Shared pointer to Visual.
Definition: gz/rendering/RenderTypes.hh:269
bool trackWorldFrame
Track point relative to target in world frame.
Definition: gz/rendering/base/BaseCamera.hh:232
virtual unsigned int ImageMemorySize() const override
Get the total image memory size in bytes.
Definition: gz/rendering/base/BaseCamera.hh:311
virtual double TrackPGain() const override
Get the camera track rotation P gain.
Definition: gz/rendering/base/BaseCamera.hh:744
@ CPT_ORTHOGRAPHIC
Orthographic projection.
Definition: gz/rendering/Camera.hh:44
T endl(T... args)
virtual void SetFollowPGain(const double _pGain) override
Set follow P Gain. Determines how fast the camera moves to follow the target node....
Definition: gz/rendering/base/BaseCamera.hh:782
virtual void AddRenderPass(const RenderPassPtr &_pass) override
Add a render pass to the camera.
Definition: gz/rendering/base/BaseCamera.hh:813
double farClip
Far clipping plane distance.
Definition: gz/rendering/base/BaseCamera.hh:217
virtual void SetShadowsDirty() override
Definition: gz/rendering/base/BaseCamera.hh:841
virtual PixelFormat ImageFormat() const override
Get the image pixel format. If the image pixel format has not been set with a valid value,...
Definition: gz/rendering/base/BaseCamera.hh:321
virtual void Update() override
Renders a new frame. This is a convenience function for single-camera scenes. It wraps the pre-render...
Definition: gz/rendering/base/BaseCamera.hh:414
virtual math::Vector2i Project(const math::Vector3d &_pt) const override
Project point in 3d world space to 2d screen space.
Definition: gz/rendering/base/BaseCamera.hh:608
shared_ptr< RenderWindow > RenderWindowPtr
Shared pointer to RenderWindow.
Definition: gz/rendering/RenderTypes.hh:243
math::Angle hfov
Horizontal camera field of view.
Definition: gz/rendering/base/BaseCamera.hh:223
virtual void SetFollowOffset(const math::Vector3d &_offset) override
Set offset of camera from target node being followed. The offset will be in the frame that is specifi...
Definition: gz/rendering/base/BaseCamera.hh:775
NodePtr trackNode
Target node to track if camera tracking is on.
Definition: gz/rendering/base/BaseCamera.hh:229
virtual unsigned int ImageHeight() const override
Get the image height in pixels.
Definition: gz/rendering/base/BaseCamera.hh:295
virtual PixelFormat Format() const =0
Set the render target image format.
virtual void PostRender() override
Preforms any necessary final rendering work. Once rendering is complete the camera will alert any lis...
Definition: gz/rendering/base/BaseCamera.hh:397
Definition: gz/rendering/base/BaseCamera.hh:44
virtual void SetWidth(const unsigned int _width)=0
Set the render target width in pixels.
virtual void SetFarClipPlane(const double _far) override
Set the camera's far clipping plane distance.
Definition: gz/rendering/base/BaseCamera.hh:685
math::Matrix4d projectionMatrix
Custom projection matrix.
Definition: gz/rendering/base/BaseCamera.hh:257
virtual double AspectRatio() const override
Get the camera's aspect ratio.
Definition: gz/rendering/base/BaseCamera.hh:650
virtual void RemoveRenderPass(const RenderPassPtr &_pass)=0
Remove a render pass from the render target.
virtual CameraProjectionType ProjectionType() const override
Get the projection type for this camera.
Definition: gz/rendering/base/BaseCamera.hh:601
virtual void SetTrackTarget(const NodePtr &_target, const math::Vector3d &_offset, const bool _worldFrame) override
Set a node for camera to track. The camera will automatically change its orientation to face the targ...
Definition: gz/rendering/base/BaseCamera.hh:706
virtual math::Angle HFOV() const override
Get the camera's horizontal field-of-view.
Definition: gz/rendering/base/BaseCamera.hh:627
virtual VisualPtr VisualAt(const gz::math::Vector2i &_mousePos) override
Get the visual for a given mouse position param[in] _mousePos mouse position.
Definition: gz/rendering/base/BaseCamera.hh:634
virtual Image CreateImage() const override
Created an empty image buffer for capturing images. The resulting image will have sufficient memory a...
Definition: gz/rendering/base/BaseCamera.hh:404
virtual void PostRender()=0
Call this function after you're done updating ALL cameras.
virtual void SetHeight(const unsigned int _height)=0
Set the render target height in pixels.
virtual void SetTrackOffset(const math::Vector3d &_offset) override
Set track offset. Camera will track a point that's at an offset from the target node....
Definition: gz/rendering/base/BaseCamera.hh:730
virtual void SetNearClipPlane(const double _near) override
Set the camera's near clipping plane distance.
Definition: gz/rendering/base/BaseCamera.hh:699
virtual void SetFormat(PixelFormat _format)=0
Set the render target image format.
unsigned int antiAliasing
Anti-aliasing.
Definition: gz/rendering/base/BaseCamera.hh:226
Quaternion< T > & Rot()
#define IGN_COMMON_WARN_RESUME__DLL_INTERFACE_MISSING
virtual NodePtr FollowTarget() const override
Get the target node being followed.
Definition: gz/rendering/base/BaseCamera.hh:761