MRPT  1.9.9
CLogFileRecord.h
Go to the documentation of this file.
1 /* +------------------------------------------------------------------------+
2  | Mobile Robot Programming Toolkit (MRPT) |
3  | https://www.mrpt.org/ |
4  | |
5  | Copyright (c) 2005-2020, Individual contributors, see AUTHORS file |
6  | See: https://www.mrpt.org/Authors - All rights reserved. |
7  | Released under BSD License. See: https://www.mrpt.org/License |
8  +------------------------------------------------------------------------+ */
9 #pragma once
10 
11 #include <mrpt/io/CMemoryStream.h>
15 #include <vector>
16 
21 
22 namespace mrpt::nav
23 {
24 /** A class for storing, saving and loading a reactive navigation
25  * log record for the CReactiveNavigationSystem class.
26  * \sa CReactiveNavigationSystem, CHolonomicLogFileRecord
27  * \ingroup nav_reactive
28  */
30 {
32 
33  public:
34  /** Constructor, builds an empty record. */
36 
37  /** The structure used to store all relevant information about each
38  * transformation into TP-Space.
39  * \ingroup nav_reactive */
40  struct TInfoPerPTG
41  {
42  /** A short description for the applied PTG */
43  std::string PTG_desc;
44  /** Distances until obstacles, in "pseudometers", first index for -PI
45  * direction, last one for PI direction. */
47  /** Target(s) location in TP-Space */
48  std::vector<mrpt::math::TPoint2D> TP_Targets;
49  /** Robot location in TP-Space: normally (0,0), except during "NOP cmd
50  * vel" steps */
52  /** Time, in seconds. */
54  /** The results from the holonomic method. */
56  /** Final score of this candidate */
57  double evaluation;
58  /** Evaluation factors */
60  /** Other useful info about holonomic method execution. */
62  /** Only for the FIRST entry in a log file, this will contain a copy of
63  * the PTG with trajectories, suitable to render trajectories, etc. */
65  /** Clearance for each path */
67  };
68 
70  /** The number of PTGS: */
71  uint32_t nPTGs{0};
72  /** The info for each applied PTG: must contain "nPTGs * nSecDistances"
73  * elements */
74  std::vector<TInfoPerPTG> infoPerPTG;
75  /** The selected PTG. */
76  int32_t nSelectedPTG{-1};
77 
78  /** Known values:
79  * - "executionTime": The total computation time, excluding sensing.
80  * - "estimatedExecutionPeriod": The estimated execution period.
81  */
82  std::map<std::string, double> values;
83  /** Known values:
84  * - "tim_start_iteration": Time of start of navigationStep()
85  *implementation.
86  * - "tim_send_cmd_vel": Time of sending cmdvel to robot.
87  * - "curPoseAndVel": Time of querying robot pose and velocities.
88  */
89  std::map<std::string, mrpt::system::TTimeStamp> timestamps;
90  /** Additional debug traces */
91  std::map<std::string, std::string> additional_debug_msgs;
92  /** The WS-Obstacles */
94  /** The robot pose (from odometry and from the localization/SLAM system). */
97  relPoseVelCmd; //! Relative poses (wrt to robotPoseLocalization) for
98  //! extrapolated paths at two instants: time of obstacle
99  //! sense, and future pose of motion comman
100  /** The relative location of target(s) in Workspace. */
101  std::vector<mrpt::math::TPose2D> WS_targets_relative;
102 
103  /** The final motion command sent to robot, in "m/sec" and "rad/sec". */
105  /** Motion command as comes out from the PTG, before scaling speed limit
106  * filtering. */
108  /** The actual robot velocities in global (map) coordinates, as read from
109  * sensors, in "m/sec" and "rad/sec". */
111  /** The actual robot velocities in local (robot) coordinates, as read from
112  * sensors, in "m/sec" and "rad/sec". */
114 
115  /** The robot shape in WS. Used by PTGs derived from
116  * mrpt::nav::CPTG_RobotShape_Polygonal */
118  /** The circular robot radius. Used by PTGs derived from
119  * mrpt::nav::CPTG_RobotShape_Circular */
120  double robotShape_radius{.0};
121 
122  // "NOP motion command" mode variables:
123  /** Negative means no NOP mode evaluation, so the rest of "NOP variables"
124  * should be ignored. */
125  int16_t ptg_index_NOP{-1};
126  uint16_t ptg_last_k_NOP{0};
131 };
132 } // namespace mrpt::nav
CHolonomicLogFileRecord::Ptr HLFR
Other useful info about holonomic method execution.
mrpt::math::TPose2D rel_cur_pose_wrt_last_vel_cmd_NOP
int32_t nSelectedPTG
The selected PTG.
std::vector< mrpt::math::TPose2D > WS_targets_relative
Relative poses (wrt to robotPoseLocalization) for.
mrpt::math::CVectorFloat robotShape_y
mrpt::math::TTwist2D cur_vel_local
The actual robot velocities in local (robot) coordinates, as read from sensors, in "m/sec" and "rad/s...
Template for column vectors of dynamic size, compatible with Eigen.
std::map< std::string, mrpt::system::TTimeStamp > timestamps
Known values:
mrpt::nav::ClearanceDiagram clearance
Clearance for each path.
mrpt::math::TPose2D rel_pose_PTG_origin_wrt_sense_NOP
mrpt::math::TPose2D robotPoseOdometry
mrpt::nav::CParameterizedTrajectoryGenerator::Ptr ptg
Only for the FIRST entry in a log file, this will contain a copy of the PTG with trajectories, suitable to render trajectories, etc.
mrpt::math::TPose2D relPoseSense
std::vector< mrpt::math::TPoint2D > TP_Targets
Target(s) location in TP-Space.
A cloud of points in 2D or 3D, which can be built from a sequence of laser scans. ...
uint32_t nPTGs
The number of PTGS:
Clearance information for one particular PTG and one set of obstacles.
A class for storing, saving and loading a reactive navigation log record for the CReactiveNavigationS...
mrpt::math::CVectorFloat robotShape_x
The robot shape in WS.
CLogFileRecord()
Constructor, builds an empty record.
2D twist: 2D velocity vector (vx,vy) + planar angular velocity (omega)
Definition: TTwist2D.h:19
mrpt::nav::CParameterizedTrajectoryGenerator::TNavDynamicState ptg_last_navDynState
double desiredDirection
The results from the holonomic method.
mrpt::system::TParametersDouble evalFactors
Evaluation factors.
mrpt::math::TPose2D robotPoseLocalization
The robot pose (from odometry and from the localization/SLAM system).
mrpt::kinematics::CVehicleVelCmd::Ptr cmd_vel
The final motion command sent to robot, in "m/sec" and "rad/sec".
mrpt::math::TPoint2D TP_Robot
Robot location in TP-Space: normally (0,0), except during "NOP cmd vel" steps.
double timeForTPObsTransformation
Time, in seconds.
int16_t ptg_index_NOP
Negative means no NOP mode evaluation, so the rest of "NOP variables" should be ignored.
mrpt::maps::CSimplePointsMap WS_Obstacles_original
std::map< std::string, double > values
Known values:
std::string PTG_desc
A short description for the applied PTG.
mrpt::math::CVectorFloat TP_Obstacles
Distances until obstacles, in "pseudometers", first index for -PI direction, last one for PI directio...
mrpt::nav::CParameterizedTrajectoryGenerator::TNavDynamicState navDynState
std::vector< TInfoPerPTG > infoPerPTG
The info for each applied PTG: must contain "nPTGs * nSecDistances" elements.
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/se...
Lightweight 2D pose.
Definition: TPose2D.h:22
The virtual base class which provides a unified interface for all persistent objects in MRPT...
Definition: CSerializable.h:30
#define DEFINE_SERIALIZABLE(class_name, NS)
This declaration must be inserted in all CSerializable classes definition, within the class declarati...
mrpt::maps::CSimplePointsMap WS_Obstacles
The WS-Obstacles.
Dynamic state that may affect the PTG path parameterization.
mrpt::math::TPose2D relPoseVelCmd
The structure used to store all relevant information about each transformation into TP-Space...
double evaluation
Final score of this candidate.
std::map< std::string, std::string > additional_debug_msgs
Additional debug traces.
double robotShape_radius
The circular robot radius.



Page generated by Doxygen 1.8.14 for MRPT 1.9.9 Git: c7a3bec24 Sun Mar 29 18:33:13 2020 +0200 at dom mar 29 18:50:38 CEST 2020