class mrpt::nav::CLogFileRecord

A class for storing, saving and loading a reactive navigation log record for the CReactiveNavigationSystem class.

See also:

CReactiveNavigationSystem, CHolonomicLogFileRecord

#include <mrpt/nav/reactive/CLogFileRecord.h>

class CLogFileRecord: public mrpt::serialization::CSerializable
{
public:
    // structs

    struct TInfoPerPTG;

    //
fields

    mrpt::nav::CParameterizedTrajectoryGenerator::TNavDynamicState navDynState;
    uint32_t nPTGs {0};
    std::vector<TInfoPerPTG> infoPerPTG;
    int32_t nSelectedPTG {-1};
    std::map<std::string, double> values;
    std::map<std::string, mrpt::system::TTimeStamp> timestamps;
    std::map<std::string, std::string> additional_debug_msgs;
    mrpt::maps::CSimplePointsMap WS_Obstacles;
    mrpt::maps::CSimplePointsMap WS_Obstacles_original;
    mrpt::math::TPose2D robotPoseLocalization;
    mrpt::math::TPose2D robotPoseOdometry;
    mrpt::math::TPose2D relPoseSense;
    mrpt::math::TPose2D relPoseVelCmd;
    std::vector<mrpt::math::TPose2D> WS_targets_relative;
    mrpt::kinematics::CVehicleVelCmd::Ptr cmd_vel;
    mrpt::kinematics::CVehicleVelCmd::Ptr cmd_vel_original;
    mrpt::math::TTwist2D cur_vel;
    mrpt::math::TTwist2D cur_vel_local;
    mrpt::math::CVectorFloat robotShape_x;
    mrpt::math::CVectorFloat robotShape_y;
    double robotShape_radius {.0};
    int16_t ptg_index_NOP {-1};
    uint16_t ptg_last_k_NOP {0};
    mrpt::math::TPose2D rel_cur_pose_wrt_last_vel_cmd_NOP;
    mrpt::math::TPose2D rel_pose_PTG_origin_wrt_sense_NOP;
    mrpt::nav::CParameterizedTrajectoryGenerator::TNavDynamicState ptg_last_navDynState;

    // construction

    CLogFileRecord();
};

Fields

uint32_t nPTGs {0}

The number of PTGS:

std::vector<TInfoPerPTG> infoPerPTG

The info for each applied PTG: must contain “nPTGs * nSecDistances” elements.

int32_t nSelectedPTG {-1}

The selected PTG.

std::map<std::string, double> values

Known values:

  • “executionTime”: The total computation time, excluding sensing.

  • “estimatedExecutionPeriod”: The estimated execution period.

std::map<std::string, mrpt::system::TTimeStamp> timestamps

Known values:

  • “tim_start_iteration”: Time of start of navigationStep() implementation.

  • “tim_send_cmd_vel”: Time of sending cmdvel to robot.

  • “curPoseAndVel”: Time of querying robot pose and velocities.

std::map<std::string, std::string> additional_debug_msgs

Additional debug traces.

mrpt::maps::CSimplePointsMap WS_Obstacles

The WS-Obstacles (in the local robot frame of reference)

mrpt::math::TPose2D robotPoseLocalization

The robot pose (from odometry and from the localization/SLAM system).

mrpt::math::TPose2D relPoseSense

Relative poses (wrt to robotPoseLocalization) for extrapolated paths at two instants: time of obstacle sense, and future pose of motion command.

std::vector<mrpt::math::TPose2D> WS_targets_relative

The relative location of target(s) in Workspace (wrt the robot).

mrpt::kinematics::CVehicleVelCmd::Ptr cmd_vel

The final motion command sent to robot, in “m/sec” and “rad/sec”.

mrpt::kinematics::CVehicleVelCmd::Ptr cmd_vel_original

Motion command as comes out from the PTG, before scaling speed limit filtering.

mrpt::math::TTwist2D cur_vel

The actual robot velocities in global (map) coordinates, as read from sensors, in “m/sec” and “rad/sec”.

mrpt::math::TTwist2D cur_vel_local

The actual robot velocities in local (robot) coordinates, as read from sensors, in “m/sec” and “rad/sec”.

mrpt::math::CVectorFloat robotShape_x

The robot shape in WS.

Used by PTGs derived from mrpt::nav::CPTG_RobotShape_Polygonal

double robotShape_radius {.0}

The circular robot radius.

Used by PTGs derived from mrpt::nav::CPTG_RobotShape_Circular

int16_t ptg_index_NOP {-1}

Negative means no NOP mode evaluation, so the rest of “NOP variables” should be ignored.

Construction

CLogFileRecord()

Constructor, builds an empty record.