29 robotPoseLocalization(0, 0, 0),
30 robotPoseOdometry(0, 0, 0),
31 relPoseSense(0, 0, 0),
32 relPoseVelCmd(0, 0, 0),
33 WS_targets_relative(),
35 cur_vel_local(0, 0, 0),
36 robotShape_radius(.0),
39 rel_cur_pose_wrt_last_vel_cmd_NOP(0, 0, 0),
40 rel_pose_PTG_origin_wrt_sense_NOP(0, 0, 0)
54 for (i = 0; i <
n; i++)
62 (
const void*)&(*
infoPerPTG[i].TP_Obstacles.begin()),
68 out <<
infoPerPTG[i].timeForTPObsTransformation
78 const bool there_is_ptg_data =
infoPerPTG[i].ptg ? true :
false;
79 out << there_is_ptg_data;
80 if (there_is_ptg_data) out <<
infoPerPTG[i].ptg;
178 for (i = 0; i <
n; i++)
187 ipp.TP_Obstacles.resize(m);
189 in.ReadBufferFixEndianness(&(*ipp.TP_Obstacles.begin()), m);
191 ipp.TP_Targets.clear();
196 in >> ipp.TP_Targets;
202 ipp.TP_Targets.push_back(trg);
209 ipp.TP_Targets.push_back(
219 in >> ipp.timeForTPObsTransformation >>
220 ipp.timeForHolonomicMethod;
221 in >> ipp.desiredDirection >> ipp.desiredSpeed >>
226 in.ReadAsAndCastTo<float,
double>(
227 ipp.timeForTPObsTransformation);
228 in.ReadAsAndCastTo<float,
double>(
229 ipp.timeForHolonomicMethod);
230 in.ReadAsAndCastTo<float,
double>(ipp.desiredDirection);
231 in.ReadAsAndCastTo<float,
double>(ipp.desiredSpeed);
232 in.ReadAsAndCastTo<float,
double>(ipp.evaluation);
234 if (version >= 21 && version < 23)
236 double evaluation_org, evaluation_priority;
237 in >> evaluation_org >> evaluation_priority;
246 bool there_is_ptg_data;
247 in >> there_is_ptg_data;
248 if (there_is_ptg_data)
249 ipp.ptg = std::dynamic_pointer_cast<
257 std::vector<std::map<double, double>> raw_clearances;
258 in >> raw_clearances;
259 ipp.clearance.resize(
260 raw_clearances.size(), raw_clearances.size());
261 for (
size_t k = 0; k < raw_clearances.size(); k++)
262 ipp.clearance.get_path_clearance_decimated(k) =
267 ipp.clearance.readFromStream(
in);
272 ipp.clearance.clear();
289 in >> robotOdometryPose;
331 crel_pose_PTG_origin_wrt_sense_NOP;
332 in >> crel_cur_pose_wrt_last_vel_cmd_NOP >>
333 crel_pose_PTG_origin_wrt_sense_NOP;
335 crel_cur_pose_wrt_last_vel_cmd_NOP.
asTPose();
337 crel_pose_PTG_origin_wrt_sense_NOP.asTPose();
344 if (version >= 17 && version < 24)
361 std::vector<double> vel;
369 for (
size_t k = 0; k <
cmd_vel->getVelCmdLength(); k++)
370 cmd_vel->setVelCmdElement(i, vel[k]);
389 values[
"executionTime"] = old_exec_time;
399 if (
n)
in.ReadBufferFixEndianness(&(*prevV.begin()),
n);
403 if (
n)
in.ReadBufferFixEndianness(&(*prevW.begin()),
n);
406 prevSelPTG.resize(
n);
407 if (
n)
in.ReadBufferFixEndianness(&(*prevSelPTG.begin()),
n);
427 float actual_v, actual_w;
428 in >> actual_v >> actual_w;
439 if (version < 13 && version > 1)
441 float old_estim_period;
442 in >> old_estim_period;
443 values[
"estimatedExecutionPeriod"] = old_estim_period;
458 for (
unsigned int j = 0; j <
n; j++)
481 for (i = 0; i < n; i++) in >> dummy;
494 in >> navigatorBehavior;
500 in >> doorCrossing_P1 >> doorCrossing_P2;
504 if (version > 6 && version < 13)
520 if (version >= 12 && version < 15)
522 std::vector<std::vector<double>> dummy_cmd_vel_filterings;
523 in >> dummy_cmd_vel_filterings;
545 in >> crelPoseSense >> crelPoseVelCmd;
void readFromStream(mrpt::serialization::CArchive &in)
mrpt::math::TPose2D rel_cur_pose_wrt_last_vel_cmd_NOP
void serializeFrom(mrpt::serialization::CArchive &in, uint8_t serial_version) override
Pure virtual method for reading (deserializing) from an abstract archive.
uint8_t serializeGetVersion() const override
Must return the current versioning number of the object.
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...
void serializeTo(mrpt::serialization::CArchive &out) const override
Pure virtual method for writing (serializing) to an abstract archive.
GLboolean GLenum GLenum GLvoid * values
std::map< std::string, mrpt::system::TTimeStamp > timestamps
Known values:
#define IMPLEMENTS_SERIALIZABLE(class_name, base, NameSpace)
This must be inserted in all CSerializable classes implementation files.
mrpt::math::TPose2D rel_pose_PTG_origin_wrt_sense_NOP
mrpt::math::TPose2D robotPoseOdometry
mrpt::math::TPose2D relPoseSense
Column vector, like Eigen::MatrixX*, but automatically initialized to zeros since construction...
uint32_t nPTGs
The number of PTGS:
void WriteBuffer(const void *Buffer, size_t Count)
Writes a block of bytes to the stream from Buffer.
A class for storing, saving and loading a reactive navigation log record for the CReactiveNavigationS...
GLubyte GLubyte GLubyte GLubyte w
mrpt::math::CVectorFloat robotShape_x
The robot shape in WS.
mrpt::math::TPose2D asTPose() const
#define MRPT_THROW_UNKNOWN_SERIALIZATION_VERSION(__V)
For use in CSerializable implementations.
2D twist: 2D velocity vector (vx,vy) + planar angular velocity (omega)
mrpt::Clock::time_point TTimeStamp
A system independent time type, it holds the the number of 100-nanosecond intervals since January 1...
mrpt::nav::CParameterizedTrajectoryGenerator::TNavDynamicState ptg_last_navDynState
This is the base class for any user-defined PTG.
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::TTwist2D curVelLocal
Current vehicle velocity (local frame of reference)
int16_t ptg_index_NOP
Negative means no NOP mode evaluation, so the rest of "NOP variables" should be ignored.
mrpt::aligned_std_vector< TInfoPerPTG > infoPerPTG
The info for each applied PTG: must contain "nPTGs * nSecDistances" elements.
mrpt::math::TPose2D relTarget
Current relative target location.
mrpt::maps::CSimplePointsMap WS_Obstacles_original
GLsizei const GLchar ** string
A class used to store a 2D point.
void writeToStream(mrpt::serialization::CArchive &out) const
Virtual base class for "archives": classes abstracting I/O streams.
mrpt::nav::CParameterizedTrajectoryGenerator::TNavDynamicState navDynState
A class used to store a 2D pose, including the 2D coordinate point and a heading (phi) angle...
mrpt::kinematics::CVehicleVelCmd::Ptr cmd_vel_original
Motion command as comes out from the PTG, before scaling speed limit filtering.
std::string format(const char *fmt,...) MRPT_printf_format_check(1
A std::string version of C sprintf.
mrpt::math::TTwist2D cur_vel
The actual robot velocities in global (map) coordinates, as read from sensors, in "m/sec" and "rad/se...
mrpt::maps::CSimplePointsMap WS_Obstacles
The WS-Obstacles.
std::shared_ptr< CVehicleVelCmd > Ptr
unsigned __int32 uint32_t
Dynamic state that may affect the PTG path parameterization.
mrpt::math::TPose2D relPoseVelCmd
Kinematic model for Ackermann-like or differential-driven vehicles.
std::map< std::string, std::string > additional_debug_msgs
Additional debug traces.
double robotShape_radius
The circular robot radius.