class mrpt::obs::CObservationSkeleton¶
This class stores a skeleton as tracked by OPENNI2 & NITE2 libraries from PrimeSense sensors.
Class introduced in MRPT 1.3.1
See also:
#include <mrpt/obs/CObservationSkeleton.h> class CObservationSkeleton: public mrpt::obs::CObservation { public: // structs struct TSkeletonJoint; // fields mrpt::poses::CPose3D sensorPose; TSkeletonJoint head; TSkeletonJoint neck; TSkeletonJoint torso; TSkeletonJoint left_shoulder; TSkeletonJoint left_elbow; TSkeletonJoint left_hand; TSkeletonJoint left_hip; TSkeletonJoint left_knee; TSkeletonJoint left_foot; TSkeletonJoint right_shoulder; TSkeletonJoint right_elbow; TSkeletonJoint right_hand; TSkeletonJoint right_hip; TSkeletonJoint right_knee; TSkeletonJoint right_foot; // methods 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¶
mrpt::poses::CPose3D sensorPose
The pose of the sensor on the robot.
TSkeletonJoint head
The skeleton joints (15)
Methods¶
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:
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:
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