Gazebo Rendering

API Reference

3.7.2
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  // \sa Camera::SetMaterial(const MaterialPtr &) override;
119  public: virtual void SetMaterial(const MaterialPtr &_material)
120  override;
121 
122  // Documentation inherited.
123  public: virtual void SetTrackTarget(const NodePtr &_target,
124  const math::Vector3d &_offset,
125  const bool _worldFrame) override;
126 
127  // Documentation inherited.
128  public: virtual NodePtr TrackTarget() const override;
129 
130  // Documentation inherited.
131  public: virtual void SetTrackOffset(const math::Vector3d &_offset)
132  override;
133 
134  // Documentation inherited.
135  public: virtual math::Vector3d TrackOffset() const override;
136 
137  // Documentation inherited.
138  public: virtual void SetTrackPGain(const double _pGain) override;
139 
140  // Documentation inherited.
141  public: virtual double TrackPGain() const override;
142 
143  // Documentation inherited.
144  public: virtual void SetFollowTarget(const NodePtr &_target,
145  const math::Vector3d &_Offset, const bool _worldFrame)
146  override;
147 
148  // Documentation inherited.
149  public: virtual NodePtr FollowTarget() const override;
150 
151  // Documentation inherited.
152  public: virtual void SetFollowOffset(const math::Vector3d &_offset)
153  override;
154 
155  // Documentation inherited.
156  public: virtual math::Vector3d FollowOffset() const override;
157 
158  // Documentation inherited.
159  public: virtual void SetFollowPGain(const double _pGain) override;
160 
161  // Documentation inherited.
162  public: virtual double FollowPGain() const override;
163 
164  // Documentation inherited.
165  public: virtual unsigned int RenderTextureGLId() const override;
166 
167  // Documentation inherited.
168  public: virtual void AddRenderPass(const RenderPassPtr &_pass) override;
169 
170  // Documentation inherited.
171  public: virtual void RemoveRenderPass(const RenderPassPtr &_pass)
172  override;
173 
174  // Documentation inherited.
175  public: virtual unsigned int RenderPassCount() const override;
176 
177  // Documentation inherited.
178  public: virtual RenderPassPtr RenderPassByIndex(unsigned int _index)
179  const override;
180 
181  protected: virtual void *CreateImageBuffer() const;
182 
183  protected: virtual void Load() override;
184 
185  protected: virtual void Reset();
186 
187  protected: virtual RenderTargetPtr RenderTarget() const = 0;
188 
190  protected: common::EventT<void(const void *, unsigned int, unsigned int,
191  unsigned int, const std::string &)> newFrameEvent;
192 
193  protected: ImagePtr imageBuffer;
194 
196  protected: double nearClip = 0.01;
197 
199  protected: double farClip = 1000.0;
200 
202  protected: double aspect = 1.3333333;
203 
205  protected: math::Angle hfov;
206 
208  protected: unsigned int antiAliasing = 0u;
209 
211  protected: NodePtr trackNode;
212 
214  protected: bool trackWorldFrame = false;
215 
219 
222  protected: double trackPGain = 1.0;
223 
225  protected: NodePtr followNode;
227 
229  protected: bool followWorldFrame = false;
230 
233  protected: double followPGain = 1.0;
234 
237 
238  friend class BaseDepthCamera<T>;
239  };
240 
242  template <class T>
244  {
245  }
246 
248  template <class T>
250  {
251  }
252 
254  template <class T>
255  unsigned int BaseCamera<T>::ImageWidth() const
256  {
257  return this->RenderTarget()->Width();
258  }
259 
261  template <class T>
262  void BaseCamera<T>::SetImageWidth(const unsigned int _width)
263  {
264  this->RenderTarget()->SetWidth(_width);
265  }
266 
268  template <class T>
269  unsigned int BaseCamera<T>::ImageHeight() const
270  {
271  return this->RenderTarget()->Height();
272  }
273 
275  template <class T>
276  void BaseCamera<T>::SetImageHeight(const unsigned int _height)
277  {
278  this->RenderTarget()->SetHeight(_height);
279  }
280 
282  template <class T>
283  unsigned int BaseCamera<T>::ImageMemorySize() const
284  {
285  PixelFormat format = this->ImageFormat();
286  unsigned int width = this->ImageWidth();
287  unsigned int height = this->ImageHeight();
288  return PixelUtil::MemorySize(format, width, height);
289  }
290 
292  template <class T>
294  {
295  return this->RenderTarget()->Format();
296  }
297 
299  template <class T>
301  {
302  this->RenderTarget()->SetFormat(_format);
303  }
304 
306  template <class T>
308  {
309  T::PreRender();
310 
311  this->RenderTarget()->PreRender();
312 
313  // camera following
314  if (this->followNode)
315  {
316  // tether camera fixed in world frame
317  if (this->followWorldFrame)
318  {
319  math::Vector3d targetCamPos =
320  this->followNode->WorldPosition() + this->followOffset;
321  math::Vector3d pos = this->WorldPosition() +
322  (targetCamPos - this->WorldPosition()) * this->followPGain;
323  this->SetWorldPosition(pos);
324  }
325  // tether camera fixed in target's local frame
326  else
327  {
328  math::Pose3d targetCamPose = math::Pose3d(this->followOffset,
329  this->WorldRotation());
330  targetCamPose += this->followNode->WorldPose();
331 
332  math::Vector3d pos = this->WorldPosition() +
333  (targetCamPose.Pos() - this->WorldPosition()) * this->followPGain;
334  this->SetWorldPosition(pos);
335  }
336  }
337 
338  // camera tracking
339  if (this->trackNode)
340  {
341  math::Vector3d eye = this->WorldPosition();
342  math::Pose3d targetPose = math::Pose3d(this->trackOffset,
344  if (this->trackWorldFrame)
345  {
346  targetPose.Pos() += this->trackNode->WorldPosition();
347  }
348  else
349  {
350  targetPose += this->trackNode->WorldPose();
351  }
352 
353  math::Pose3d p =
354  math::Matrix4d::LookAt(eye, targetPose.Pos()).Pose();
355 
356  math::Quaterniond q = p.Rot();
357  // skip slerp if we don't need it
358  if (!math::equal(this->trackPGain, 1.0))
359  {
361  this->trackPGain, this->WorldRotation(), p.Rot(), true);
362  }
363  this->SetWorldRotation(q);
364  }
365  }
366 
368  template <class T>
370  {
371  this->RenderTarget()->PostRender();
372  }
373 
375  template <class T>
377  {
378  PixelFormat format = this->ImageFormat();
379  unsigned int width = this->ImageWidth();
380  unsigned int height = this->ImageHeight();
381  return Image(width, height, format);
382  }
383 
385  template <class T>
387  {
388  this->Scene()->PreRender();
389  this->Render();
390  this->PostRender();
391  }
392 
394  template <class T>
396  {
397  this->Update();
398  this->Copy(_image);
399  }
400 
402  template <class T>
403  void BaseCamera<T>::Copy(Image &_image) const
404  {
405  this->RenderTarget()->Copy(_image);
406  }
407 
409  template <class T>
410  bool BaseCamera<T>::SaveFrame(const std::string &/*_name*/)
411  {
412  return false;
413  }
414 
416  template <class T>
418  Camera::NewFrameListener _listener)
419  {
420  return newFrameEvent.Connect(_listener);
421  }
422 
424  template <class T>
426  {
427  // TODO(anyone): determine proper type
428  unsigned int size = this->ImageMemorySize();
429  return new unsigned char *[size];
430  }
431 
433  template <class T>
435  {
436  T::Load();
437  }
438 
440  template <class T>
442  {
443  math::Angle fov;
444  fov.Degree(60);
445  this->SetImageWidth(1);
446  this->SetImageHeight(1);
447  this->SetImageFormat(PF_R8G8B8);
448  this->SetAspectRatio(1.33333);
449  this->SetAntiAliasing(0u);
450  this->SetHFOV(fov);
451  this->SetNearClipPlane(0.01);
452  this->SetFarClipPlane(1000);
453  }
454 
456  template <class T>
458  {
459  // Does nothing by default
460  ignerr << "Render window not supported for render engine: " <<
461  this->Scene()->Engine()->Name() << std::endl;
462  return RenderWindowPtr();
463  }
464 
466  template <class T>
468  {
469  // perspective projection
470  double ratio = this->AspectRatio();
471  double fov = this->HFOV().Radian();
472  double vfov = 2.0 * std::atan(std::tan(fov / 2.0) / ratio);
473  double f = 1.0;
474  double _near = this->NearClipPlane();
475  double _far = this->FarClipPlane();
476  double top = _near * std::tan(0.5*vfov) / f;
477  double height = 2 * top;
478  double width = ratio * height;
479  double left = -0.5 * width;
480  double right = left + width;
481  double bottom = top - height;
482 
483  double invw = 1.0 / (right - left);
484  double invh = 1.0 / (top - bottom);
485  double invd = 1.0 / (_far - _near);
486  double x = 2 * _near * invw;
487  double y = 2 * _near * invh;
488  double a = (right + left) * invw;
489  double b = (top + bottom) * invh;
490  double c = -(_far + _near) * invd;
491  double d = -2 * _far * _near * invd;
492  math::Matrix4d result;
493  result(0, 0) = x;
494  result(0, 2) = a;
495  result(1, 1) = y;
496  result(1, 2) = b;
497  result(2, 2) = c;
498  result(2, 3) = d;
499  result(3, 2) = -1;
500 
501  // TODO(anyone): compute projection matrix for orthographic camera
502 
503  return result;
504  }
505 
507  template <class T>
509  {
510  math::Matrix3d r(this->WorldPose().Rot());
511  // transform from y up to z up
512  math::Matrix3d tf(0, 0, -1,
513  -1, 0, 0,
514  0, 1, 0);
515  r = r * tf;
516  r.Transpose();
517  math::Vector3d t = r * this->WorldPose().Pos() * -1;
518  math::Matrix4d result;
519  result = r;
520  result.SetTranslation(t);
521  result(3, 3) = 1.0;
522  return result;
523  }
524 
526  template <class T>
528  {
529  return this->hfov;
530  }
531 
533  template <class T>
534  VisualPtr BaseCamera<T>::VisualAt(const gz::math::Vector2i
535  &/*_mousePos*/)
536  {
537  ignerr << "VisualAt not implemented for the render engine" << std::endl;
538  return VisualPtr();
539  }
540 
542  template <class T>
544  {
545  this->hfov = _hfov;
546  }
547 
549  template <class T>
551  {
552  return this->aspect;
553  }
554 
556  template <class T>
557  void BaseCamera<T>::SetAspectRatio(const double _aspect)
558  {
559  this->aspect = _aspect;
560  }
561 
563  template <class T>
564  unsigned int BaseCamera<T>::AntiAliasing() const
565  {
566  return this->antiAliasing;
567  }
568 
570  template <class T>
571  void BaseCamera<T>::SetAntiAliasing(const unsigned int _aa)
572  {
573  this->antiAliasing = _aa;
574  }
575 
577  template <class T>
579  {
580  return this->farClip;
581  }
582 
584  template <class T>
585  void BaseCamera<T>::SetFarClipPlane(const double _far)
586  {
587  this->farClip = _far;
588  }
589 
591  template <class T>
593  {
594  return this->nearClip;
595  }
596 
598  template <class T>
599  void BaseCamera<T>::SetNearClipPlane(const double _near)
600  {
601  this->nearClip = _near;
602  }
603 
605  template <class T>
607  const math::Vector3d &_offset, const bool _worldFrame)
608  {
609  this->trackNode = _target;
610  this->trackWorldFrame = _worldFrame;
611  this->trackOffset = _offset;
612  }
613 
615  template <class T>
617  {
618  return this->trackNode;
619  }
620 
622  template <class T>
624  {
625  return this->trackOffset;
626  }
627 
629  template <class T>
631  {
632  this->trackOffset = _offset;
633  }
634 
636  template <class T>
637  void BaseCamera<T>::SetTrackPGain(const double _pGain)
638  {
639  this->trackPGain = math::clamp(_pGain, 0.0, 1.0);
640  }
641 
643  template <class T>
645  {
646  return this->trackPGain;
647  }
648 
650  template <class T>
652  const math::Vector3d &_offset, const bool _worldFrame)
653  {
654  this->followNode = _target;
655  this->followWorldFrame = _worldFrame;
656  this->followOffset = _offset;
657  }
658 
660  template <class T>
662  {
663  return this->followNode;
664  }
665 
667  template <class T>
669  {
670  return this->followOffset;
671  }
672 
674  template <class T>
676  {
677  this->followOffset = _offset;
678  }
679 
681  template <class T>
682  void BaseCamera<T>::SetFollowPGain(const double _pGain)
683  {
684  this->followPGain = math::clamp(_pGain, 0.0, 1.0);
685  }
686 
688  template <class T>
690  {
691  return this->followPGain;
692  }
693 
695  template <class T>
696  void BaseCamera<T>::SetMaterial(const MaterialPtr &/*_material*/)
697  {
698  ignerr << "SetMaterial not implemented for current render"
699  << " engine" << std::endl;
700  }
701 
703  template <class T>
704  unsigned int BaseCamera<T>::RenderTextureGLId() const
705  {
706  ignerr << "RenderTextureGLId is not supported by current render"
707  << " engine" << std::endl;
708  return 0u;
709  }
710 
712  template <class T>
714  {
715  this->RenderTarget()->AddRenderPass(_pass);
716  }
717 
719  template <class T>
721  {
722  this->RenderTarget()->RemoveRenderPass(_pass);
723  }
724 
726  template <class T>
727  unsigned int BaseCamera<T>::RenderPassCount() const
728  {
729  return this->RenderTarget()->RenderPassCount();
730  }
731 
733  template <class T>
735  {
736  return this->RenderTarget()->RenderPassByIndex(_index);
737  }
738  }
739  }
740 }
741 #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:734
double followPGain
P gain for follow mode. Determines how fast the camera moves to follow the target node....
Definition: gz/rendering/base/BaseCamera.hh:233
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:704
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:218
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:410
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:191
ImagePtr imageBuffer
Definition: gz/rendering/base/BaseCamera.hh:193
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:425
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:417
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:651
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:457
double trackPGain
P gain for tracking. Determines how fast the camera rotates to look at the target node....
Definition: gz/rendering/base/BaseCamera.hh:222
virtual void SetImageFormat(PixelFormat _format) override
Set the image pixel format.
Definition: gz/rendering/base/BaseCamera.hh:300
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:467
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:571
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:276
BaseCamera()
Definition: gz/rendering/base/BaseCamera.hh:243
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:637
virtual ~BaseCamera()
Definition: gz/rendering/base/BaseCamera.hh:249
virtual unsigned int Height() const =0
Get render target height in pixels.
double nearClip
Near clipping plane distance.
Definition: gz/rendering/base/BaseCamera.hh:196
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:578
static const Quaternion Identity
Posable camera used for rendering the scene graph.
Definition: gz/rendering/Camera.hh:40
virtual void Copy(Image &_image) const =0
Write rendered image to given Image. The RenderTarget will convert the underlying image to the specif...
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:202
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:623
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:395
#define ignerr
Pose3< double > Pose3d
math::Vector3d followOffset
Offset distance between camera and target node being followed.
Definition: gz/rendering/base/BaseCamera.hh:236
Manages a single scene-graph. This class updates scene-wide properties and holds the root scene node....
Definition: gz/rendering/Scene.hh:48
virtual void SetImageWidth(const unsigned int _width) override
Set the image width in pixels.
Definition: gz/rendering/base/BaseCamera.hh:262
virtual NodePtr TrackTarget() const override
Get the target node being tracked.
Definition: gz/rendering/base/BaseCamera.hh:616
virtual void RemoveRenderPass(const RenderPassPtr &_pass) override
Remove a render pass from the camera.
Definition: gz/rendering/base/BaseCamera.hh:720
virtual unsigned int AntiAliasing() const override
Get the level of anti-aliasing used during rendering.
Definition: gz/rendering/base/BaseCamera.hh:564
virtual unsigned int ImageWidth() const override
Get the image width in pixels.
Definition: gz/rendering/base/BaseCamera.hh:255
virtual void SetHFOV(const math::Angle &_hfov) override
Set the camera's horizontal field-of-view.
Definition: gz/rendering/base/BaseCamera.hh:543
virtual RenderPassPtr RenderPassByIndex(unsigned int _index) const =0
Get a render pass by index.
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:592
virtual void SetMaterial(const MaterialPtr &_material) override
Set a material that the camera should see on all objects.
Definition: gz/rendering/base/BaseCamera.hh:696
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:689
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:727
T clamp(T _v, T _min, T _max)
T atan(T... args)
virtual void Reset()
Definition: gz/rendering/base/BaseCamera.hh:441
virtual void Load() override
Definition: gz/rendering/base/BaseCamera.hh:434
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:307
bool followWorldFrame
Follow target in world frame.
Definition: gz/rendering/base/BaseCamera.hh:229
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:668
virtual math::Matrix4d ViewMatrix() const override
Get the view matrix for this camera.
Definition: gz/rendering/base/BaseCamera.hh:508
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:403
NodePtr followNode
Target node to follow.
Definition: gz/rendering/base/BaseCamera.hh:225
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:557
shared_ptr< Visual > VisualPtr
Shared pointer to Visual.
Definition: gz/rendering/RenderTypes.hh:217
bool trackWorldFrame
Track point relative to target in world frame.
Definition: gz/rendering/base/BaseCamera.hh:214
virtual unsigned int ImageMemorySize() const override
Get the total image memory size in bytes.
Definition: gz/rendering/base/BaseCamera.hh:283
virtual double TrackPGain() const override
Get the camera track rotation P gain.
Definition: gz/rendering/base/BaseCamera.hh:644
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:682
virtual void AddRenderPass(const RenderPassPtr &_pass) override
Add a render pass to the camera.
Definition: gz/rendering/base/BaseCamera.hh:713
double farClip
Far clipping plane distance.
Definition: gz/rendering/base/BaseCamera.hh:199
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:293
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:386
shared_ptr< RenderWindow > RenderWindowPtr
Shared pointer to RenderWindow.
Definition: gz/rendering/RenderTypes.hh:191
math::Angle hfov
Horizontal camera field of view.
Definition: gz/rendering/base/BaseCamera.hh:205
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:675
NodePtr trackNode
Target node to track if camera tracking is on.
Definition: gz/rendering/base/BaseCamera.hh:211
virtual unsigned int ImageHeight() const override
Get the image height in pixels.
Definition: gz/rendering/base/BaseCamera.hh:269
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:369
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:585
virtual double AspectRatio() const override
Get the camera's aspect ratio.
Definition: gz/rendering/base/BaseCamera.hh:550
virtual void RemoveRenderPass(const RenderPassPtr &_pass)=0
Remove a render pass from the render target.
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:606
virtual math::Angle HFOV() const override
Get the camera's horizontal field-of-view.
Definition: gz/rendering/base/BaseCamera.hh:527
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:534
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:376
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:630
virtual void SetNearClipPlane(const double _near) override
Set the camera's near clipping plane distance.
Definition: gz/rendering/base/BaseCamera.hh:599
virtual void SetFormat(PixelFormat _format)=0
Set the render target image format.
unsigned int antiAliasing
Anti-aliasing.
Definition: gz/rendering/base/BaseCamera.hh:208
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:661