class mrpt::obs::CObservationBearingRange

This observation represents a number of range-bearing value pairs, each one for a detected landmark, which optionally can have identification IDs.

This class can manage sensors that detect landmarks in a 2D plane (e.g. a laser scanner) or in the 3D space (e.g. a camera). There are two direction angles: yaw (azimuth) and pitch (negative elevation). For 2D sensors, the pitch must be always set to 0. See CObservationBearingRange::validCovariances for the instructions to fill the uncertainty covariances.

See also:

CObservation

#include <mrpt/obs/CObservationBearingRange.h>

class CObservationBearingRange: public mrpt::obs::CObservation
{
public:
    // typedefs

    typedef std::vector<TMeasurement> TMeasurementList;

    // structs

    struct TMeasurement;

    //
fields

    float minSensorDistance {0};
    float maxSensorDistance {0};
    float fieldOfView_yaw = mrpt::d2f(180.0_deg);
    float fieldOfView_pitch = mrpt::d2f(90.0_deg);
    mrpt::poses::CPose3D sensorLocationOnRobot;
    TMeasurementList sensedData;
    bool validCovariances {false};
    float sensor_std_range {0};
    float sensor_std_yaw {0};
    float sensor_std_pitch {0};

    //
methods

    void debugPrintOut();
    virtual void getSensorPose(mrpt::poses::CPose3D& out_sensorPose) const;
    virtual void setSensorPose(const mrpt::poses::CPose3D& newSensorPose);
    virtual void getDescriptionAsText(std::ostream& o) 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;
    virtual void load() const;
    virtual void unload();

    template <class METRICMAP>
    bool insertObservationInto(
        METRICMAP* theMap,
        const mrpt::poses::CPose3D* robotPose = nullptr
        ) const;

    virtual void getSensorPose(mrpt::poses::CPose3D& out_sensorPose) const = 0;
    void getSensorPose(mrpt::math::TPose3D& out_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;
    std::string getDescriptionAsTextValue() const;

Fields

float fieldOfView_yaw = mrpt::d2f(180.0_deg)

Information about the.

sensor: Ranges, in meters (0: there is no limits) Information about the sensor: The “field-of-view” of the sensor, in radians (for yaw ).

float fieldOfView_pitch = mrpt::d2f(90.0_deg)

Information about the sensor: The “field-of-view” of the sensor, in radians (for pitch ).

mrpt::poses::CPose3D sensorLocationOnRobot

The position of the sensor on the robot.

TMeasurementList sensedData

The list of observed ranges:

bool validCovariances {false}

True: The individual 3x3 covariance matrices must be taken into account, false (default): All the measurements have identical, diagonal 3x3 covariance matrices given by the values sensor_std_range,sensor_std_yaw,sensor_std_pitch.

float sensor_std_range {0}

Taken into account only if validCovariances=false: the standard deviation of the sensor noise model for range,yaw and pitch (in meters and radians).

If validCovariances=true, these 3 values are ignored and the individual 3x3 covariance matrices contain the actual uncertainties for each of the detected landmarks.

Methods

void debugPrintOut()

Prints out the contents of the object.

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