class mrpt::opengl::CAngularObservationMesh

Overview

A mesh built from a set of 2D laser scan observations.

Each element of this set is a single scan through the yaw, given a specific pitch. Each scan has a mrpt::poses::CPose3D identifying the origin of the scan, which ideally is the same for every one of them.

#include <mrpt/opengl/CAngularObservationMesh.h>

class CAngularObservationMesh:
    public mrpt::opengl::CRenderizableShaderTriangles,
    public mrpt::opengl::CRenderizableShaderWireFrame
{
public:
    // structs

    struct TDoubleRange;

    // classes

    template <class T>
    class FTrace1D;

    template <class T>
    class FTrace2D;

    // construction

    CAngularObservationMesh();

    // methods

    virtual void freeOpenGLResources();
    virtual void render(const RenderContext& rc) const;
    virtual void renderUpdateBuffers() const;
    virtual shader_list_t requiredShaders() const;
    virtual void onUpdateBuffers_Wireframe();
    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);
    virtual auto internalBoundingBoxLocal() const;
    bool isWireframe() const;
    void setWireframe(bool enabled = true);
    bool isTransparencyEnabled() const;
    void enableTransparency(bool enabled = true);
    virtual bool traceRay(const mrpt::poses::CPose3D& o, double& dist) const;
    void setPitchBounds(const double initial, const double final);
    void setPitchBounds(const std::vector<double>& bounds);
    void getPitchBounds(double& initial, double& final) const;
    void getPitchBounds(std::vector<double>& bounds) const;
    void getScanSet(std::vector<mrpt::obs::CObservation2DRangeScan>& scans) const;
    bool setScanSet(const std::vector<mrpt::obs::CObservation2DRangeScan>& scans);
    void generateSetOfTriangles(CSetOfTriangles::Ptr& res) const;
    void generatePointCloud(mrpt::maps::CPointsMap* out_map) const;
    void getTracedRays(CSetOfLines::Ptr& res) const;
    void getUntracedRays(CSetOfLines::Ptr& res, double dist) const;
    void generateSetOfTriangles(std::vector<mrpt::math::TPolygon3D>& res) const;
    void getActualMesh(mrpt::math::CMatrixDynamic<mrpt::math::TPoint3D_data<double>>& pts, mrpt::math::CMatrixBool& validity) const;
    void cullFaces(const TCullFace& cf);
    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;
    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;

    template <class T>
    static void trace2DSetOfRays(
        const T& e,
        const mrpt::poses::CPose3D& initial,
        CAngularObservationMesh::Ptr& caom,
        const TDoubleRange& pitchs,
        const TDoubleRange& yaws
        );

    template <class T>
    static void trace1DSetOfRays(
        const T& e,
        const mrpt::poses::CPose3D& initial,
        mrpt::obs::CObservation2DRangeScan& obs,
        const TDoubleRange& yaws
        );
};

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;
    virtual void onUpdateBuffers_Wireframe() = 0;

Construction

CAngularObservationMesh()

Basic constructor.

Methods

virtual void freeOpenGLResources()

Free opengl buffers.

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:

renderUpdateBuffers

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 shader_list_t requiredShaders() const

Returns the ID of the OpenGL shader program required to render this class.

See also:

DefaultShaderID

virtual void onUpdateBuffers_Wireframe()

Must be implemented in derived classes to update the geometric entities to be drawn in “m_*_buffer” fields.

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:

setVisibility

void setVisibility(bool visible = true)

Set object visibility (default=true)

See also:

isVisible

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:

enableShowName

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

virtual auto 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()

bool isWireframe() const

Returns whether the object is configured as wireframe or solid.

void setWireframe(bool enabled = true)

Sets the display mode for the object.

True=wireframe, False=solid.

bool isTransparencyEnabled() const

Returns whether the object may be transparent or not.

void enableTransparency(bool enabled = true)

Enables or disables transparencies.

virtual bool traceRay(const mrpt::poses::CPose3D& o, double& dist) const

Traces a ray to the object, returning the distance to a given pose through its X axis.

See also:

mrpt::opengl::CRenderizable, trace2DSetOfRays, trace1DSetOfRays

void setPitchBounds(const double initial, const double final)

Sets the pitch bounds for this range.

void setPitchBounds(const std::vector<double>& bounds)

Sets the pitch bounds for this range.

void getPitchBounds(double& initial, double& final) const

Gets the initial and final pitch bounds for this range.

void getPitchBounds(std::vector<double>& bounds) const

Gets the pitch bounds for this range.

void getScanSet(std::vector<mrpt::obs::CObservation2DRangeScan>& scans) const

Gets the scan set.

bool setScanSet(const std::vector<mrpt::obs::CObservation2DRangeScan>& scans)

Sets the scan set.

void generateSetOfTriangles(CSetOfTriangles::Ptr& res) const

Gets the mesh as a set of triangles, for displaying them.

See also:

generateSetOfTriangles (std::vector<TPolygon3D> &), mrpt::opengl::CSetOfTriangles,mrpt::opengl::mrpt::opengl::TTriangle

void generatePointCloud(mrpt::maps::CPointsMap* out_map) const

Returns the scanned points as a 3D point cloud.

The target pointmap must be passed as a pointer to allow the use of any derived class.

void getTracedRays(CSetOfLines::Ptr& res) const

Gets a set of lines containing the traced rays, for displaying them.

See also:

getUntracedRays, mrpt::opengl::CSetOfLines

void getUntracedRays(CSetOfLines::Ptr& res, double dist) const

Gets a set of lines containing the untraced rays, up to a specified distance, for displaying them.

See also:

getTracedRays, mrpt::opengl::CSetOfLines

void generateSetOfTriangles(std::vector<mrpt::math::TPolygon3D>& res) const

Gets the mesh as a set of polygons, to work with them.

See also:

generateSetOfTriangles(mrpt::opengl::CSetOfTriangles &)

void getActualMesh(mrpt::math::CMatrixDynamic<mrpt::math::TPoint3D_data<double>>& pts, mrpt::math::CMatrixBool& validity) const

Retrieves the full mesh, along with the validity matrix.

void cullFaces(const TCullFace& cf)

Control whether to render the FRONT, BACK, or BOTH (default) set of faces.

Refer to docs for glCullFace(). Example: If set to cullFaces(TCullFace::BACK);, back faces will not be drawn (“culled”)

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.

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:

enableShowName()

virtual void initializeTextures() const

Initializes all textures (loads them into opengl memory).

template <class T>
static void trace2DSetOfRays(
    const T& e,
    const mrpt::poses::CPose3D& initial,
    CAngularObservationMesh::Ptr& caom,
    const TDoubleRange& pitchs,
    const TDoubleRange& yaws
    )

2D ray tracing (will generate a 3D mesh).

Given an object and two ranges, realizes a scan from the initial pose and stores it in a CAngularObservationMesh object. The objective may be a Scene, a CRenderizable or any children of its.

See also:

mrpt::opengl::CRenderizable, mrpt::opengl::Scene.

template <class T>
static void trace1DSetOfRays(
    const T& e,
    const mrpt::poses::CPose3D& initial,
    mrpt::obs::CObservation2DRangeScan& obs,
    const TDoubleRange& yaws
    )

2D ray tracing (will generate a vectorial mesh inside a plane).

Given an object and a range, realizes a scan from the initial pose and stores it in a CObservation2DRangeScan object. The objective may be a Scene, a CRenderizable or any children of its.

See also:

mrpt::opengl::CRenderizable, mrpt::opengl::Scene.