Main MRPT website > C++ reference for MRPT 1.3.2
obs/CObservation.h
Go to the documentation of this file.
1 /* +---------------------------------------------------------------------------+
2  | Mobile Robot Programming Toolkit (MRPT) |
3  | http://www.mrpt.org/ |
4  | |
5  | Copyright (c) 2005-2015, Individual contributors, see AUTHORS file |
6  | See: http://www.mrpt.org/Authors - All rights reserved. |
7  | Released under BSD License. See details in http://www.mrpt.org/License |
8  +---------------------------------------------------------------------------+ */
9 #ifndef COBSERVATION_H
10 #define COBSERVATION_H
11 
12 
13 #include <mrpt/obs/link_pragmas.h>
14 
16 //#include <mrpt/utils/CStream.h>
17 //#include <mrpt/system/os.h>
18 #include <mrpt/system/datetime.h>
19 #include <mrpt/math/math_frwds.h>
20 
21 namespace mrpt
22 {
23  /** This namespace contains algorithms for SLAM, localization, map building, representation of robot's actions and observations, and representation of many kinds of metric maps.
24  */
25  namespace obs
26  {
27  /** Used for CObservationBearingRange::TMeasurement::beaconID
28  * \ingroup mrpt_obs_grp
29  */
30  #define INVALID_LANDMARK_ID (-1)
31 
32  /** Used for CObservationBeaconRange
33  * \ingroup mrpt_obs_grp
34  */
35  #define INVALID_BEACON_ID (-1)
36 
38 
39  /** Declares a class that represents any robot's observation.
40  * This is a base class for many types of sensor observations.
41  * Users can add new observation types creating a new class deriving from this one.
42  *
43  * <b>IMPORTANT</b>: Observations don't include any information about the robot pose,
44  * just raw sensory data and, where aplicable, information about the sensor position and
45  * orientation in the local frame of the robot.
46  *
47  * \sa CSensoryFrame, CMetricMap
48  * \ingroup mrpt_obs_grp
49  */
50  class OBS_IMPEXP CObservation : public mrpt::utils::CSerializable
51  {
52  // This must be added to any CSerializable derived class:
54 
55  protected:
56  void swap(CObservation &o); //!< Swap with another observation, ONLY the data defined here in the base class CObservation. It's protected since it'll be only called from child classes that should know what else to swap appart from these common data.
57 
58  public:
59 
60  /** @name Data common to any observation
61  @{ */
62 
63  /** The associated time-stamp.
64  */
65  mrpt::system::TTimeStamp timestamp;
66 
67  /** An arbitrary label that can be used to identify the sensor.
68  */
69  std::string sensorLabel;
70 
71  /** @} */
72 
73  /** Constructor: It sets the initial timestamp to current time
74  */
75  CObservation();
76 
77 
78  /** This method is equivalent to:
79  * \code
80  * map->insertObservation(this, robotPose)
81  * \endcode
82  * \param theMap The map where this observation is to be inserted: the map will be updated.
83  * \param robotPose The pose of the robot base for this observation, relative to the target metric map. Set to NULL (default) to use (0,0,0deg)
84  *
85  * \return Returns true if the map has been updated, or false if this observations
86  * has nothing to do with a metric map (for example, a sound observation).
87  *
88  * \sa CMetricMap, CMetricMap::insertObservation
89  */
90  template <class METRICMAP>
91  inline bool insertObservationInto( METRICMAP *theMap, const mrpt::poses::CPose3D *robotPose = NULL ) const
92  {
93  return theMap->insertObservation(this,robotPose);
94  }
95 
96  /** A general method to retrieve the sensor pose on the robot.
97  * Note that most sensors will return a full (6D) CPose3D, but see the derived classes for more details or special cases.
98  * \sa setSensorPose
99  */
100  virtual void getSensorPose( mrpt::poses::CPose3D &out_sensorPose ) const = 0;
101 
102  /** A general method to retrieve the sensor pose on the robot.
103  * Note that most sensors will return a full (6D) CPose3D, but see the derived classes for more details or special cases.
104  * \sa setSensorPose
105  */
106  void getSensorPose( mrpt::math::TPose3D &out_sensorPose ) const;
107 
108  /** A general method to change the sensor pose on the robot.
109  * Note that most sensors will use the full (6D) CPose3D, but see the derived classes for more details or special cases.
110  * \sa getSensorPose
111  */
112  virtual void setSensorPose( const mrpt::poses::CPose3D &newSensorPose ) = 0;
113 
114  /** A general method to change the sensor pose on the robot.
115  * Note that most sensors will use the full (6D) CPose3D, but see the derived classes for more details or special cases.
116  * \sa getSensorPose
117  */
118  void setSensorPose( const mrpt::math::TPose3D &newSensorPose );
119 
120  /** Build a detailed, multi-line textual description of the observation contents and dump it to the output stream.
121  * \note If overried by derived classes, call base CObservation::getDescriptionAsText() first to show common information.
122  * \note This is the text that appears in RawLogViewer when selecting an object in the dataset */
123  virtual void getDescriptionAsText(std::ostream &o) const;
124 
125  /** @name Delayed-load manual control methods.
126  @{ */
127 
128  /** Makes sure all images and other fields which may be externally stored are loaded in memory.
129  * Note that for all CImages, calling load() is not required since the images will be automatically loaded upon first access, so load() shouldn't be needed to be called in normal cases by the user.
130  * If all the data were alredy loaded or this object has no externally stored data fields, calling this method has no effects.
131  * \sa unload
132  */
133  virtual void load() const { /* Default implementation: do nothing */ }
134  /** Unload all images, for the case they being delayed-load images stored in external files (othewise, has no effect).
135  * \sa load
136  */
137  virtual void unload() { /* Default implementation: do nothing */ }
138 
139  /** @} */
140 
141  }; // End of class def.
143 
144 
145  } // End of namespace
146 } // End of namespace
147 
148 #endif
uint64_t TTimeStamp
A system independent time type, it holds the the number of 100-nanosecond intervals since January 1...
Definition: datetime.h:30
The virtual base class which provides a unified interface for all persistent objects in MRPT...
Definition: CSerializable.h:39
STL namespace.
#define DEFINE_VIRTUAL_SERIALIZABLE(class_name)
This declaration must be inserted in virtual CSerializable classes definition:
#define DEFINE_SERIALIZABLE_PRE_CUSTOM_BASE_LINKAGE(class_name, base_name, _LINKAGE_)
This declaration must be inserted in all CSerializable classes definition, before the class declarati...
class BASE_IMPEXP CSerializable
Definition: CStream.h:23
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
virtual void unload()
Unload all images, for the case they being delayed-load images stored in external files (othewise...
A class used to store a 3D pose (a 3D translation + a rotation in 3D).
Definition: CPose3D.h:72
Declares a class that represents any robot's observation.
Lightweight 3D pose (three spatial coordinates, plus three angular coordinates).
virtual void load() const
Makes sure all images and other fields which may be externally stored are loaded in memory...
#define DEFINE_SERIALIZABLE_POST_CUSTOM_BASE_LINKAGE(class_name, base_name, _LINKAGE_)



Page generated by Doxygen 1.8.9.1 for MRPT 1.3.2 SVN:Unversioned directory at Tue Dec 8 09:49:21 UTC 2015