A class for storing, saving and loading a reactive navigation log record for the CReactiveNavigationSystem class.
Definition at line 33 of file CLogFileRecord.h.
#include <mrpt/nav/reactive/CLogFileRecord.h>
Classes | |
struct | TInfoPerPTG |
The structure used to store all relevant information about each transformation into TP-Space. More... | |
Public Member Functions | |
void * | operator new (size_t size) |
void * | operator new[] (size_t size) |
void | operator delete (void *ptr) throw () |
void | operator delete[] (void *ptr) throw () |
void | operator delete (void *memory, void *ptr) throw () |
void * | operator new (size_t size, const std::nothrow_t &) throw () |
void | operator delete (void *ptr, const std::nothrow_t &) throw () |
CLogFileRecord () | |
Constructor, builds an empty record. More... | |
virtual mxArray * | writeToMatlab () const |
Introduces a pure virtual method responsible for writing to a mxArray Matlab object, typically a MATLAB struct whose contents are documented in each derived class. More... | |
CObject * | clone () const |
Cloning interface for smart pointers. More... | |
RTTI classes and functions | |
mrpt::utils::CObjectPtr | duplicateGetSmartPtr () const |
Returns a copy of the object, indepently of its class, as a smart pointer (the newly created object will exist as long as any copy of this smart pointer). More... | |
Static Public Member Functions | |
static void * | operator new (size_t size, void *ptr) |
Public Attributes | |
mrpt::nav::CParameterizedTrajectoryGenerator::TNavDynamicState | navDynState |
uint32_t | nPTGs |
The number of PTGS: More... | |
mrpt::aligned_containers< TInfoPerPTG >::vector_t | infoPerPTG |
The info for each applied PTG: must contain "nPTGs * nSecDistances" elements. More... | |
int32_t | nSelectedPTG |
The selected PTG. More... | |
std::map< std::string, double > | values |
Known values: More... | |
std::map< std::string, mrpt::system::TTimeStamp > | timestamps |
Known values: More... | |
std::map< std::string, std::string > | additional_debug_msgs |
Additional debug traces. More... | |
mrpt::maps::CSimplePointsMap | WS_Obstacles |
mrpt::maps::CSimplePointsMap | WS_Obstacles_original |
The WS-Obstacles. More... | |
mrpt::math::TPose2D | robotPoseLocalization |
mrpt::math::TPose2D | robotPoseOdometry |
The robot pose (from odometry and from the localization/SLAM system). More... | |
mrpt::math::TPose2D | relPoseSense |
mrpt::math::TPose2D | relPoseVelCmd |
std::vector< mrpt::math::TPose2D > | WS_targets_relative |
Relative poses (wrt to robotPoseLocalization) for extrapolated paths at two instants: time of obstacle sense, and future pose of motion comman. More... | |
mrpt::kinematics::CVehicleVelCmdPtr | cmd_vel |
The final motion command sent to robot, in "m/sec" and "rad/sec". More... | |
mrpt::kinematics::CVehicleVelCmdPtr | cmd_vel_original |
Motion command as comes out from the PTG, before scaling speed limit filtering. More... | |
mrpt::math::TTwist2D | cur_vel |
The actual robot velocities in global (map) coordinates, as read from sensors, in "m/sec" and "rad/sec". More... | |
mrpt::math::TTwist2D | cur_vel_local |
The actual robot velocities in local (robot) coordinates, as read from sensors, in "m/sec" and "rad/sec". More... | |
mrpt::math::CVectorFloat | robotShape_x |
mrpt::math::CVectorFloat | robotShape_y |
The robot shape in WS. Used by PTGs derived from mrpt::nav::CPTG_RobotShape_Polygonal. More... | |
double | robotShape_radius |
The circular robot radius. Used by PTGs derived from mrpt::nav::CPTG_RobotShape_Circular. More... | |
int16_t | ptg_index_NOP |
Negative means no NOP mode evaluation, so the rest of "NOP variables" should be ignored. More... | |
uint16_t | ptg_last_k_NOP |
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 |
Static Public Attributes | |
static const mrpt::utils::TRuntimeClassId | classCObject |
RTTI stuff | |
static const mrpt::utils::TRuntimeClassId | classCSerializable |
Protected Member Functions | |
CSerializable virtual methods | |
void | writeToStream (mrpt::utils::CStream &out, int *getVersion) const |
Introduces a pure virtual method responsible for writing to a CStream. More... | |
void | readFromStream (mrpt::utils::CStream &in, int version) |
Introduces a pure virtual method responsible for loading from a CStream This can not be used directly be users, instead use "stream >> object;" for reading it from a stream or "stream >> object_ptr;" if the class is unknown apriori. More... | |
RTTI stuff | |
typedef CLogFileRecordPtr | Ptr |
typedef CLogFileRecordPtr | ConstPtr |
static mrpt::utils::CLASSINIT | _init_CLogFileRecord |
static mrpt::utils::TRuntimeClassId | classCLogFileRecord |
static const mrpt::utils::TRuntimeClassId * | classinfo |
static const mrpt::utils::TRuntimeClassId * | _GetBaseClass () |
virtual const mrpt::utils::TRuntimeClassId * | GetRuntimeClass () const |
Returns information about the class of an object in runtime. More... | |
virtual mrpt::utils::CObject * | duplicate () const |
Returns a copy of the object, indepently of its class. More... | |
static mrpt::utils::CObject * | CreateObject () |
static CLogFileRecordPtr | Create () |
typedef CLogFileRecordPtr mrpt::nav::CLogFileRecord::ConstPtr |
Definition at line 35 of file CLogFileRecord.h.
typedef CLogFileRecordPtr mrpt::nav::CLogFileRecord::Ptr |
A typedef for the associated smart pointer
Definition at line 35 of file CLogFileRecord.h.
CLogFileRecord::CLogFileRecord | ( | ) |
Constructor, builds an empty record.
Definition at line 26 of file CLogFileRecord.cpp.
|
staticprotected |
|
inlineinherited |
|
static |
|
static |
|
virtual |
Returns a copy of the object, indepently of its class.
Implements mrpt::utils::CObject.
|
inlineinherited |
Returns a copy of the object, indepently of its class, as a smart pointer (the newly created object will exist as long as any copy of this smart pointer).
Definition at line 162 of file CObject.h.
References mrpt::utils::CObjectPtr.
Referenced by mrpt::obs::CRawlog::addActions(), mrpt::slam::CIncrementalMapPartitioner::addMapFrame(), and mrpt::obs::CRawlog::addObservations().
|
virtual |
Returns information about the class of an object in runtime.
Reimplemented from mrpt::utils::CSerializable.
Definition at line 35 of file CLogFileRecord.h.
Definition at line 35 of file CLogFileRecord.h.
|
inline |
Definition at line 35 of file CLogFileRecord.h.
Definition at line 35 of file CLogFileRecord.h.
|
inline |
Definition at line 35 of file CLogFileRecord.h.
Definition at line 35 of file CLogFileRecord.h.
|
inline |
Definition at line 35 of file CLogFileRecord.h.
|
inline |
Definition at line 35 of file CLogFileRecord.h.
|
protectedvirtual |
Introduces a pure virtual method responsible for loading from a CStream This can not be used directly be users, instead use "stream >> object;" for reading it from a stream or "stream >> object_ptr;" if the class is unknown apriori.
in | The input binary stream where the object data must read from. |
version | The version of the object stored in the stream: use this version number in your code to know how to read the incoming data. |
std::exception | On any error, see CStream::ReadBuffer |
Implements mrpt::utils::CSerializable.
Definition at line 137 of file CLogFileRecord.cpp.
References additional_debug_msgs, cmd_vel, cmd_vel_original, cur_vel, cur_vel_local, mrpt::nav::CParameterizedTrajectoryGenerator::TNavDynamicState::curVelLocal, mrpt::mrpt::format(), infoPerPTG, MRPT_THROW_UNKNOWN_SERIALIZATION_VERSION, navDynState, nPTGs, nSelectedPTG, ptg_index_NOP, ptg_last_k_NOP, ptg_last_navDynState, mrpt::nav::CParameterizedTrajectoryGenerator::TNavDynamicState::readFromStream(), rel_cur_pose_wrt_last_vel_cmd_NOP, rel_pose_PTG_origin_wrt_sense_NOP, relPoseSense, relPoseVelCmd, mrpt::nav::CParameterizedTrajectoryGenerator::TNavDynamicState::relTarget, robotPoseLocalization, robotPoseOdometry, robotShape_radius, robotShape_x, robotShape_y, timestamps, version, WS_Obstacles, WS_Obstacles_original, and WS_targets_relative.
|
inlinevirtualinherited |
Introduces a pure virtual method responsible for writing to a mxArray
Matlab object, typically a MATLAB struct
whose contents are documented in each derived class.
mxArray
(caller is responsible of memory freeing) or NULL is class does not support conversion to MATLAB. Definition at line 79 of file CSerializable.h.
|
protectedvirtual |
Introduces a pure virtual method responsible for writing to a CStream.
This can not be used directly be users, instead use "stream << object;" for writing it to a stream.
out | The output binary stream where object must be dumped. |
getVersion | If NULL, the object must be dumped. If not, only the version of the object dump must be returned in this pointer. This enables the versioning of objects dumping and backward compatibility with previously stored data. |
std::exception | On any error, see CStream::WriteBuffer |
Implements mrpt::utils::CSerializable.
Definition at line 49 of file CLogFileRecord.cpp.
References additional_debug_msgs, cmd_vel, cmd_vel_original, cur_vel, cur_vel_local, infoPerPTG, navDynState, nPTGs, nSelectedPTG, ptg_index_NOP, ptg_last_k_NOP, ptg_last_navDynState, rel_cur_pose_wrt_last_vel_cmd_NOP, rel_pose_PTG_origin_wrt_sense_NOP, relPoseSense, relPoseVelCmd, robotPoseLocalization, robotPoseOdometry, robotShape_radius, robotShape_x, robotShape_y, timestamps, version, mrpt::utils::CStream::WriteBuffer(), mrpt::nav::CParameterizedTrajectoryGenerator::TNavDynamicState::writeToStream(), WS_Obstacles, WS_Obstacles_original, and WS_targets_relative.
|
staticprotected |
Definition at line 35 of file CLogFileRecord.h.
std::map<std::string, std::string> mrpt::nav::CLogFileRecord::additional_debug_msgs |
Additional debug traces.
Definition at line 74 of file CLogFileRecord.h.
Referenced by mrpt::nav::CAbstractPTGBasedReactive::build_movement_candidate(), mrpt::nav::CAbstractPTGBasedReactive::calc_move_candidate_scores(), mrpt::nav::CAbstractPTGBasedReactive::performNavigationStep(), readFromStream(), and writeToStream().
|
static |
Definition at line 35 of file CLogFileRecord.h.
|
staticinherited |
|
staticinherited |
Definition at line 42 of file CSerializable.h.
|
static |
Definition at line 35 of file CLogFileRecord.h.
mrpt::kinematics::CVehicleVelCmdPtr mrpt::nav::CLogFileRecord::cmd_vel |
The final motion command sent to robot, in "m/sec" and "rad/sec".
Definition at line 80 of file CLogFileRecord.h.
Referenced by readFromStream(), mrpt::nav::CAbstractPTGBasedReactive::STEP8_GenerateLogRecord(), and writeToStream().
mrpt::kinematics::CVehicleVelCmdPtr mrpt::nav::CLogFileRecord::cmd_vel_original |
Motion command as comes out from the PTG, before scaling speed limit filtering.
Definition at line 81 of file CLogFileRecord.h.
Referenced by readFromStream(), and writeToStream().
mrpt::math::TTwist2D mrpt::nav::CLogFileRecord::cur_vel |
The actual robot velocities in global (map) coordinates, as read from sensors, in "m/sec" and "rad/sec".
Definition at line 82 of file CLogFileRecord.h.
Referenced by readFromStream(), mrpt::nav::CAbstractPTGBasedReactive::STEP8_GenerateLogRecord(), and writeToStream().
mrpt::math::TTwist2D mrpt::nav::CLogFileRecord::cur_vel_local |
The actual robot velocities in local (robot) coordinates, as read from sensors, in "m/sec" and "rad/sec".
Definition at line 83 of file CLogFileRecord.h.
Referenced by readFromStream(), mrpt::nav::CAbstractPTGBasedReactive::STEP8_GenerateLogRecord(), and writeToStream().
mrpt::aligned_containers<TInfoPerPTG>::vector_t mrpt::nav::CLogFileRecord::infoPerPTG |
The info for each applied PTG: must contain "nPTGs * nSecDistances" elements.
Definition at line 60 of file CLogFileRecord.h.
Referenced by mrpt::nav::CAbstractPTGBasedReactive::build_movement_candidate(), mrpt::nav::CAbstractPTGBasedReactive::performNavigationStep(), readFromStream(), mrpt::nav::CAbstractPTGBasedReactive::STEP8_GenerateLogRecord(), and writeToStream().
mrpt::nav::CParameterizedTrajectoryGenerator::TNavDynamicState mrpt::nav::CLogFileRecord::navDynState |
Definition at line 58 of file CLogFileRecord.h.
Referenced by mrpt::nav::CAbstractPTGBasedReactive::performNavigationStep(), readFromStream(), and writeToStream().
uint32_t mrpt::nav::CLogFileRecord::nPTGs |
The number of PTGS:
Definition at line 59 of file CLogFileRecord.h.
Referenced by readFromStream(), mrpt::nav::CAbstractPTGBasedReactive::STEP8_GenerateLogRecord(), and writeToStream().
int32_t mrpt::nav::CLogFileRecord::nSelectedPTG |
The selected PTG.
Definition at line 61 of file CLogFileRecord.h.
Referenced by readFromStream(), mrpt::nav::CAbstractPTGBasedReactive::STEP8_GenerateLogRecord(), and writeToStream().
int16_t mrpt::nav::CLogFileRecord::ptg_index_NOP |
Negative means no NOP mode evaluation, so the rest of "NOP variables" should be ignored.
Definition at line 89 of file CLogFileRecord.h.
Referenced by readFromStream(), mrpt::nav::CAbstractPTGBasedReactive::STEP8_GenerateLogRecord(), and writeToStream().
uint16_t mrpt::nav::CLogFileRecord::ptg_last_k_NOP |
Definition at line 90 of file CLogFileRecord.h.
Referenced by readFromStream(), mrpt::nav::CAbstractPTGBasedReactive::STEP8_GenerateLogRecord(), and writeToStream().
mrpt::nav::CParameterizedTrajectoryGenerator::TNavDynamicState mrpt::nav::CLogFileRecord::ptg_last_navDynState |
Definition at line 92 of file CLogFileRecord.h.
Referenced by readFromStream(), mrpt::nav::CAbstractPTGBasedReactive::STEP8_GenerateLogRecord(), and writeToStream().
mrpt::math::TPose2D mrpt::nav::CLogFileRecord::rel_cur_pose_wrt_last_vel_cmd_NOP |
Definition at line 91 of file CLogFileRecord.h.
Referenced by readFromStream(), mrpt::nav::CAbstractPTGBasedReactive::STEP8_GenerateLogRecord(), and writeToStream().
mrpt::math::TPose2D mrpt::nav::CLogFileRecord::rel_pose_PTG_origin_wrt_sense_NOP |
Definition at line 91 of file CLogFileRecord.h.
Referenced by readFromStream(), mrpt::nav::CAbstractPTGBasedReactive::STEP8_GenerateLogRecord(), and writeToStream().
mrpt::math::TPose2D mrpt::nav::CLogFileRecord::relPoseSense |
Definition at line 77 of file CLogFileRecord.h.
Referenced by mrpt::nav::CAbstractPTGBasedReactive::performNavigationStep(), readFromStream(), and writeToStream().
mrpt::math::TPose2D mrpt::nav::CLogFileRecord::relPoseVelCmd |
Definition at line 77 of file CLogFileRecord.h.
Referenced by mrpt::nav::CAbstractPTGBasedReactive::performNavigationStep(), readFromStream(), and writeToStream().
mrpt::math::TPose2D mrpt::nav::CLogFileRecord::robotPoseLocalization |
Definition at line 76 of file CLogFileRecord.h.
Referenced by readFromStream(), mrpt::nav::CAbstractPTGBasedReactive::STEP8_GenerateLogRecord(), and writeToStream().
mrpt::math::TPose2D mrpt::nav::CLogFileRecord::robotPoseOdometry |
The robot pose (from odometry and from the localization/SLAM system).
Definition at line 76 of file CLogFileRecord.h.
Referenced by readFromStream(), mrpt::nav::CAbstractPTGBasedReactive::STEP8_GenerateLogRecord(), and writeToStream().
double mrpt::nav::CLogFileRecord::robotShape_radius |
The circular robot radius. Used by PTGs derived from mrpt::nav::CPTG_RobotShape_Circular.
Definition at line 86 of file CLogFileRecord.h.
Referenced by mrpt::nav::CReactiveNavigationSystem::loggingGetWSObstaclesAndShape(), mrpt::nav::CReactiveNavigationSystem3D::loggingGetWSObstaclesAndShape(), readFromStream(), and writeToStream().
mrpt::math::CVectorFloat mrpt::nav::CLogFileRecord::robotShape_x |
Definition at line 85 of file CLogFileRecord.h.
Referenced by mrpt::nav::CReactiveNavigationSystem::loggingGetWSObstaclesAndShape(), mrpt::nav::CReactiveNavigationSystem3D::loggingGetWSObstaclesAndShape(), readFromStream(), and writeToStream().
mrpt::math::CVectorFloat mrpt::nav::CLogFileRecord::robotShape_y |
The robot shape in WS. Used by PTGs derived from mrpt::nav::CPTG_RobotShape_Polygonal.
Definition at line 85 of file CLogFileRecord.h.
Referenced by mrpt::nav::CReactiveNavigationSystem::loggingGetWSObstaclesAndShape(), mrpt::nav::CReactiveNavigationSystem3D::loggingGetWSObstaclesAndShape(), readFromStream(), and writeToStream().
std::map<std::string, mrpt::system::TTimeStamp> mrpt::nav::CLogFileRecord::timestamps |
Known values:
Definition at line 73 of file CLogFileRecord.h.
Referenced by mrpt::nav::CAbstractPTGBasedReactive::performNavigationStep(), readFromStream(), mrpt::nav::CAbstractPTGBasedReactive::STEP8_GenerateLogRecord(), and writeToStream().
std::map<std::string, double> mrpt::nav::CLogFileRecord::values |
Known values:
Definition at line 67 of file CLogFileRecord.h.
Referenced by mrpt::nav::CAbstractPTGBasedReactive::performNavigationStep(), and mrpt::nav::CAbstractPTGBasedReactive::STEP8_GenerateLogRecord().
mrpt::maps::CSimplePointsMap mrpt::nav::CLogFileRecord::WS_Obstacles |
Definition at line 75 of file CLogFileRecord.h.
Referenced by mrpt::nav::CReactiveNavigationSystem::loggingGetWSObstaclesAndShape(), mrpt::nav::CReactiveNavigationSystem3D::loggingGetWSObstaclesAndShape(), readFromStream(), and writeToStream().
mrpt::maps::CSimplePointsMap mrpt::nav::CLogFileRecord::WS_Obstacles_original |
The WS-Obstacles.
Definition at line 75 of file CLogFileRecord.h.
Referenced by mrpt::nav::CReactiveNavigationSystem::loggingGetWSObstaclesAndShape(), readFromStream(), and writeToStream().
std::vector<mrpt::math::TPose2D> mrpt::nav::CLogFileRecord::WS_targets_relative |
Relative poses (wrt to robotPoseLocalization) for extrapolated paths at two instants: time of obstacle sense, and future pose of motion comman.
The relative location of target(s) in Workspace.
Definition at line 78 of file CLogFileRecord.h.
Referenced by readFromStream(), mrpt::nav::CAbstractPTGBasedReactive::STEP8_GenerateLogRecord(), and writeToStream().
Page generated by Doxygen 1.8.14 for MRPT 1.5.9 Git: 690a4699f Wed Apr 15 19:29:53 2020 +0200 at miƩ abr 15 19:30:12 CEST 2020 |