gz/rendering/base/BaseCamera.hh
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.
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
void Transpose()
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