class mrpt::opengl::CArrow
Overview
A 3D arrow.
See also:
#include <mrpt/opengl/CArrow.h> class CArrow: public mrpt::opengl::CRenderizableShaderTriangles { public: // construction CArrow( float x0 = 0, float y0 = 0, float z0 = 0, float x1 = 1, float y1 = 1, float z1 = 1, float headRatio = 0.2f, float smallRadius = 0.05f, float largeRadius = 0.2f ); CArrow( const mrpt::math::TPoint3Df& from, const mrpt::math::TPoint3Df& to, float headRatio = 0.2f, float smallRadius = 0.05f, float largeRadius = 0.2f ); // methods virtual void onUpdateBuffers_Triangles(); void setName(const std::string& n); std::string getName() const; bool isVisible() const; void setVisibility(bool visible = true); bool castShadows() const; void castShadows(bool doCast = true); void enableShowName(bool showName = true); bool isShowNameEnabled() const; CRenderizable& setPose(const mrpt::poses::CPose3D& o); CRenderizable& setPose(const mrpt::poses::CPose2D& o); CRenderizable& setPose(const mrpt::math::TPose3D& o); CRenderizable& setPose(const mrpt::math::TPose2D& o); CRenderizable& setPose(const mrpt::poses::CPoint3D& o); CRenderizable& setPose(const mrpt::poses::CPoint2D& o); mrpt::math::TPose3D getPose() const; mrpt::poses::CPose3D getCPose() const; CRenderizable& setLocation(double x, double y, double z); CRenderizable& setLocation(const mrpt::math::TPoint3D& p); mrpt::img::TColorf getColor() const; mrpt::img::TColor getColor_u8() const; CRenderizable& setColorA(const float a); virtual CRenderizable& setColorA_u8(const uint8_t a); float materialShininess() const; void materialShininess(float shininess); CRenderizable& setScale(float s); CRenderizable& setScale(float sx, float sy, float sz); float getScaleX() const; float getScaleY() const; float getScaleZ() const; CRenderizable& setColor(const mrpt::img::TColorf& c); CRenderizable& setColor(float R, float G, float B, float A = 1); CRenderizable& setColor_u8(uint8_t R, uint8_t G, uint8_t B, uint8_t A = 255); void setArrowEnds( float x0, float y0, float z0, float x1, float y1, float z1 ); template <typename Vector3Like> void setArrowEnds( const Vector3Like& start, const Vector3Like& end ); void setHeadRatio(float rat); void setSmallRadius(float rat); void setLargeRadius(float rat); void setSlicesCount(uint32_t slices); uint32_t getSlicesCount() const; virtual mrpt::math::TBoundingBoxf internalBoundingBoxLocal() const; virtual shader_list_t requiredShaders() const; virtual void render(const RenderContext& rc) const; virtual void renderUpdateBuffers() const; virtual void freeOpenGLResources(); virtual bool cullElegible() const; virtual void toYAMLMap(mrpt::containers::yaml& propertiesMap) const; virtual void enqueueForRenderRecursive( ] const mrpt::opengl::TRenderMatrices& state, ] RenderQueue& rq, ] bool wholeInView, ] bool is1stShadowMapPass ) const; virtual bool isCompositeObject() const; void updateBuffers() const; void notifyChange() const; bool hasToUpdateBuffers() const; virtual bool traceRay(const mrpt::poses::CPose3D& o, double& dist) const; auto getBoundingBox() const; auto getBoundingBoxLocal() const; virtual mrpt::math::TPoint3Df getLocalRepresentativePoint() const; void setLocalRepresentativePoint(const mrpt::math::TPoint3Df& p); mrpt::opengl::CText& labelObject() const; virtual void initializeTextures() const; };
Inherited Members
public: // structs struct OutdatedState; struct RenderContext; struct State; // methods virtual void render(const RenderContext& rc) const = 0; virtual void renderUpdateBuffers() const = 0; virtual shader_list_t requiredShaders() const; virtual void freeOpenGLResources() = 0; virtual void onUpdateBuffers_Triangles() = 0;
Construction
CArrow( float x0 = 0, float y0 = 0, float z0 = 0, float x1 = 1, float y1 = 1, float z1 = 1, float headRatio = 0.2f, float smallRadius = 0.05f, float largeRadius = 0.2f )
Constructor.
Methods
virtual void onUpdateBuffers_Triangles()
Must be implemented in derived classes to update the geometric entities to be drawn in “m_*_buffer” fields.
void setName(const std::string& n)
Changes the name of the object.
std::string getName() const
Returns the name of the object.
bool isVisible() const
Is the object visible?
See also:
void setVisibility(bool visible = true)
Set object visibility (default=true)
See also:
bool castShadows() const
Does the object cast shadows? (default=true)
void castShadows(bool doCast = true)
Enable/disable casting shadows by this object (default=true)
void enableShowName(bool showName = true)
Enables or disables showing the name of the object as a label when rendering.
bool isShowNameEnabled() const
See also:
CRenderizable& setPose(const mrpt::poses::CPose3D& o)
Defines the SE(3) (pose=translation+rotation) of the object with respect to its parent.
CRenderizable& setPose(const mrpt::poses::CPose2D& o)
This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.
CRenderizable& setPose(const mrpt::math::TPose3D& o)
This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.
CRenderizable& setPose(const mrpt::math::TPose2D& o)
This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.
CRenderizable& setPose(const mrpt::poses::CPoint3D& o)
This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.
CRenderizable& setPose(const mrpt::poses::CPoint2D& o)
This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.
mrpt::math::TPose3D getPose() const
Returns the 3D pose of the object as TPose3D.
mrpt::poses::CPose3D getCPose() const
Returns a const ref to the 3D pose of the object as mrpt::poses::CPose3D (which explicitly contains the 3x3 rotation matrix)
CRenderizable& setLocation(double x, double y, double z)
Changes the location of the object, keeping untouched the orientation.
Returns:
a ref to this
CRenderizable& setLocation(const mrpt::math::TPoint3D& p)
Changes the location of the object, keeping untouched the orientation.
Returns:
a ref to this
mrpt::img::TColorf getColor() const
Get color components as floats in the range [0,1].
mrpt::img::TColor getColor_u8() const
Get color components as uint8_t in the range [0,255].
CRenderizable& setColorA(const float a)
Set alpha (transparency) color component in the range [0,1].
Returns:
a ref to this
virtual CRenderizable& setColorA_u8(const uint8_t a)
Set alpha (transparency) color component in the range [0,255].
Returns:
a ref to this
float materialShininess() const
Material shininess (for specular lights in shaders that support it), between 0.0f (none) to 1.0f (shiny)
void materialShininess(float shininess)
Material shininess (for specular lights in shaders that support it), between 0.0f (none) to 1.0f (shiny)
CRenderizable& setScale(float s)
Scale to apply to the object, in all three axes (default=1)
Returns:
a ref to this
CRenderizable& setScale(float sx, float sy, float sz)
Scale to apply to the object in each axis (default=1)
Returns:
a ref to this
float getScaleX() const
Get the current scaling factor in one axis.
float getScaleY() const
Get the current scaling factor in one axis.
float getScaleZ() const
Get the current scaling factor in one axis.
CRenderizable& setColor(const mrpt::img::TColorf& c)
Changes the default object color.
Returns:
a ref to this
CRenderizable& setColor(float R, float G, float B, float A = 1)
Set the color components of this object (R,G,B,Alpha, in the range 0-1)
Returns:
a ref to this
CRenderizable& setColor_u8(uint8_t R, uint8_t G, uint8_t B, uint8_t A = 255)
Set the color components of this object (R,G,B,Alpha, in the range 0-255)
Returns:
a ref to this
void setSlicesCount(uint32_t slices)
Number of radial divisions
uint32_t getSlicesCount() const
Number of radial divisions
virtual mrpt::math::TBoundingBoxf internalBoundingBoxLocal() const
Must be implemented by derived classes to provide the updated bounding box in the object local frame of coordinates.
This will be called only once after each time the derived class reports to notifyChange() that the object geometry changed.
See also:
getBoundingBox(), getBoundingBoxLocal(), getBoundingBoxLocalf()
virtual shader_list_t requiredShaders() const
Returns the ID of the OpenGL shader program required to render this class.
See also:
virtual void render(const RenderContext& rc) const
Implements the rendering of 3D objects in each class derived from CRenderizable.
This can be called more than once (one per required shader program) if the object registered several shaders.
See also:
virtual void renderUpdateBuffers() const
Called whenever m_outdatedBuffers is true: used to re-generate OpenGL vertex buffers, etc.
before they are sent for rendering in render()
virtual void freeOpenGLResources()
Free opengl buffers.
virtual bool cullElegible() const
Return false if this object should never be checked for being culled out (=not rendered if its bbox are out of the screen limits).
For example, skyboxes or other special effects.
virtual void toYAMLMap(mrpt::containers::yaml& propertiesMap) const
Used from Scene::asYAML().
(New in MRPT 2.4.2)
virtual void enqueueForRenderRecursive( ] const mrpt::opengl::TRenderMatrices& state, ] RenderQueue& rq, ] bool wholeInView, ] bool is1stShadowMapPass ) const
Process all children objects recursively, if the object is a container.
Parameters:
wholeInView |
If true, it means that the render engine has already verified that the whole bounding box lies within the visible part of the viewport, so further culling checks can be discarded. |
virtual bool isCompositeObject() const
Should return true if enqueueForRenderRecursive() is defined since the object has inner children.
Examples: CSetOfObjects, CAssimpModel.
void updateBuffers() const
Calls renderUpdateBuffers() and clear the flag that is set with notifyChange()
void notifyChange() const
Call to enable calling renderUpdateBuffers() before the next render() rendering iteration.
bool hasToUpdateBuffers() const
Returns whether notifyChange() has been invoked since the last call to renderUpdateBuffers(), meaning the latter needs to be called again before rendering.
virtual bool traceRay(const mrpt::poses::CPose3D& o, double& dist) const
Simulation of ray-trace, given a pose.
Returns true if the ray effectively collisions with the object (returning the distance to the origin of the ray in “dist”), or false in other case. “dist” variable yields undefined behaviour when false is returned
auto getBoundingBox() const
Evaluates the bounding box of this object (including possible children) in the coordinate frame of my parent object, i.e.
if this object pose changes, the bbox returned here will change too. This is in contrast with the local bbox returned by getBoundingBoxLocal()
auto getBoundingBoxLocal() const
Evaluates the bounding box of this object (including possible children) in the coordinate frame of my parent object, i.e.
if this object pose changes, the bbox returned here will change too. This is in contrast with the local bbox returned by getBoundingBoxLocal()
virtual mrpt::math::TPoint3Df getLocalRepresentativePoint() const
Provide a representative point (in object local coordinates), used to sort objects by eye-distance while rendering with transparencies (Default=[0,0,0])
void setLocalRepresentativePoint(const mrpt::math::TPoint3Df& p)
See getLocalRepresentativePoint()
mrpt::opengl::CText& labelObject() const
Returns or constructs (in its first invocation) the associated mrpt::opengl::CText object representing the label of the object.
See also:
virtual void initializeTextures() const
Initializes all textures (loads them into opengl memory).