class mrpt::obs::CObservationStereoImages

Observation class for either a pair of left+right or left+disparity images from a stereo camera.

To find whether the observation contains a right image and/or a disparity image, see the fields hasImageDisparity and hasImageRight, respectively. This figure illustrates the coordinate frames involved in this class:

_images/CObservationStereoImages_figRefSystem.png

The images stored in this class can be raw or undistorted images. In the latter case, the “distortion” params of the corresponding “leftCamera” and “rightCamera” fields should be all zeros.

See also:

CObservation

#include <mrpt/obs/CObservationStereoImages.h>

class CObservationStereoImages: public mrpt::obs::CObservation
{
public:
    //
fields

    mrpt::img::CImage imageLeft;
    mrpt::img::CImage imageRight;
    mrpt::img::CImage imageDisparity;
    bool hasImageDisparity {false};
    bool hasImageRight {false};
    mrpt::img::TCamera leftCamera;
    mrpt::img::TCamera rightCamera;
    mrpt::poses::CPose3DQuat cameraPose;
    mrpt::poses::CPose3DQuat rightCameraPose;

    // construction

    CObservationStereoImages();

    //
methods

    void getStereoCameraParams(mrpt::img::TStereoCamera& out_params) const;
    mrpt::img::TStereoCamera getStereoCameraParams() const;
    void setStereoCameraParams(const mrpt::img::TStereoCamera& in_params);
    bool areImagesRectified() const;
    virtual void getSensorPose(mrpt::poses::CPose3D& out_sensorPose) const;
    virtual void setSensorPose(const mrpt::poses::CPose3D& newSensorPose);
    virtual void getDescriptionAsText(std::ostream& o) const;
    void swap(CObservationStereoImages& o);
    virtual void load_impl() const;
};

Inherited Members

public:
    //
fields

    mrpt::system::TTimeStamp timestamp {mrpt::system::now()};
    std::string sensorLabel;

    //
methods

    mrpt::system::TTimeStamp getTimeStamp() const;
    virtual mrpt::system::TTimeStamp getOriginalReceivedTimeStamp() const;
    void load() const;
    virtual void unload() const;
    virtual bool exportTxtSupported() const;
    virtual std::string exportTxtHeader() const;
    virtual std::string exportTxtDataRow() const;

    template <class METRICMAP>
    bool insertObservationInto(
        METRICMAP& theMap,
        const std::optional<const mrpt::poses::CPose3D>& robotPose = std::nullopt
        ) const;

    virtual void getSensorPose(mrpt::poses::CPose3D& out_sensorPose) const = 0;
    void getSensorPose(mrpt::math::TPose3D& out_sensorPose) const;
    mrpt::math::TPose3D sensorPose() const;
    virtual void setSensorPose(const mrpt::poses::CPose3D& newSensorPose) = 0;
    void setSensorPose(const mrpt::math::TPose3D& newSensorPose);
    virtual void getDescriptionAsText(std::ostream& o) const;
    virtual std::string asString() const;

Fields

mrpt::img::CImage imageLeft

Image from the left camera (this image will be ALWAYS present)

See also:

areImagesRectified()

mrpt::img::CImage imageRight

Image from the right camera, only contains a valid image if hasImageRight == true.

See also:

areImagesRectified()

mrpt::img::CImage imageDisparity

Disparity image, only contains a valid image if hasImageDisparity == true.

The relation between the actual disparity and pixels and each value in this image is… ???????????

bool hasImageDisparity {false}

Whether imageDisparity actually contains data (Default upon construction: false)

bool hasImageRight {false}

Whether imageRight actually contains data (Default upon construction: true)

mrpt::img::TCamera leftCamera

Parameters for the left/right cameras: individual intrinsic and distortion parameters of the cameras.

See the tutorial for a discussion of these parameters.

See also:

areImagesRectified(), getStereoCameraParams()

mrpt::poses::CPose3DQuat cameraPose

The pose of the LEFT camera, relative to the robot.

mrpt::poses::CPose3DQuat rightCameraPose

The pose of the right camera, relative to the left one: Note that using the conventional reference coordinates for the left camera (x points to the right, y down), the “right” camera is situated at position (BL, 0, 0) with yaw=pitch=roll=0, where BL is the BASELINE.

Methods

void getStereoCameraParams(mrpt::img::TStereoCamera& out_params) const

Populates a TStereoCamera structure with the parameters in leftCamera, rightCamera and rightCameraPose.

See also:

areImagesRectified()

void setStereoCameraParams(const mrpt::img::TStereoCamera& in_params)

Sets leftCamera, rightCamera and rightCameraPose from a TStereoCamera structure.

bool areImagesRectified() const

This method only checks whether ALL the distortion parameters in leftCamera are set to zero, which is the convention in MRPT to denote that this pair of stereo images has been rectified.

virtual void getSensorPose(mrpt::poses::CPose3D& out_sensorPose) const

A general method to retrieve the sensor pose on the robot.

Note that most sensors will return a full (6D) CPose3D, but see the derived classes for more details or special cases.

See also:

setSensorPose

virtual void setSensorPose(const mrpt::poses::CPose3D& newSensorPose)

A general method to change the sensor pose on the robot.

Note that most sensors will use the full (6D) CPose3D, but see the derived classes for more details or special cases.

See also:

getSensorPose

virtual void getDescriptionAsText(std::ostream& o) const

Build a detailed, multi-line textual description of the observation contents and dump it to the output stream.

If overried by derived classes, call base CObservation::getDescriptionAsText() first to show common information.

This is the text that appears in RawLogViewer when selecting an object in the dataset

void swap(CObservationStereoImages& o)

Do an efficient swap of all data members of this object with “o”.