ScannerInfo.hpp
Go to the documentation of this file.
00001 //
00002 // ScannerInfo.hpp
00003 //
00004 
00005 #ifndef SCANNERINFO_HPP
00006 #define SCANNERINFO_HPP
00007 
00008 #include "../BasicDatatypes.hpp"
00009 #include "Position3D.hpp"
00010 #include "../tools/Time.hpp"
00011 #include <vector>
00012 
00013 namespace datatypes
00014 {
00015 
00016 enum ScannerType
00017 {
00018         Scannertype_UNKNOWN     = 0,
00019         Scannertype_LMS1xx      = 1
00020 };
00021 
00022 // Information about one Laserscanner which has sent a Scan
00023 class ScannerInfo : public BasicData
00024 {
00025 public:
00026 
00028         ScannerInfo();
00029         ~ScannerInfo();
00030         
00031         // Estimate the memory usage of this object
00032         virtual const UINT32 getUsedMemory() const { return sizeof(*this); };
00033         
00034         static std::string scannerTypeToString(UINT8 st);
00035 
00037         bool operator==(const ScannerInfo& other) const;
00038 
00039         typedef std::vector<std::pair<double, double> > ResolutionMap;
00040 
00042         UINT8 getDeviceID() const { return m_deviceID; }
00043         void setDeviceID(UINT8 v) { m_deviceID = v; }
00044 
00045         // Returns the type of scanner that has recorded this scan
00046         UINT8 getScannerType() const { return m_scannerType; }
00047 
00048         // Set the type of the scanner that has recorded this scan
00049         void setScannerType(UINT8 newScannerType);
00050 
00052         UINT16 getScanNumber() const { return m_scanNumber; }
00053         void setScanNumber(UINT16 v) { m_scanNumber = v; }
00054 
00055         // Returns the start angle of this scan in radians.
00056         //
00057         // Field of view of one every single scanner given in its
00058         // local coordinate system, in radians, and normalized to
00059         // [-pi, pi[
00060         //
00061         double getStartAngle() const { return m_startAngle; }
00062         void setStartAngle(double v);
00063 
00064         // Returns the end angle of this scan in radians.
00065         //
00066         // Field of view of one every single scanner given in its
00067         // local coordinate system, in radians, and normalized to
00068         // [-pi, pi[
00069         double getEndAngle() const { return m_endAngle; }
00070         void setEndAngle(double v);
00071 
00072         // Returns the start timestamp of the scan received by this scanner (in terms of the host computer clock)
00073         const Time& getStartTimestamp() const { return m_scanStartTime; }
00074 
00076         const Time& getEndTimestamp() const { return m_scanEndTime; }
00077 
00079         void setTimestamps (const Time& start, const Time& end);
00080 
00081 
00083 //      const boost::posix_time::ptime& getStartDeviceTimestamp() const { return m_scanStartDeviceTime; }
00084 
00086 //      const boost::posix_time::ptime& getEndDeviceTimestamp() const { return m_scanEndDeviceTime; }
00087 
00089 //      void setDeviceTimestamps (const boost::posix_time::ptime& start, const boost::posix_time::ptime& end);
00090 
00092         double getScanFrequency() const { return m_scanFrequency; }
00093         
00095         void setScanFrequency(double freq);
00096         
00097         // Sets the processing flags of the MRS:
00098         //
00099         // Bit 0:  ground detection performed: 0 = false, 1 = true
00100         // Bit 1:  dirt detection performed: 0 = false, 1 = true
00101         // Bit 2:  rain detection performed: 0 = false, 1 = true
00102         // Bit 5:  transparency detection performed: 0 = false, 1 = true
00103         // Bit 6:  horizontal angle offset added: 0 = false, 1 = true
00104         // Bit 10: mirror side: 0=front (for 8-Layer, tilted downward), 1=rear (for 8-layer, tilted upward)
00105         // All other flags are reserved-internal and should not be evaluated.
00106         //
00107         void setProcessingFlags(const UINT16 processingFlags);
00108         
00109         // Returns true if the scan was scanned with the rear mirror side. In 8-layer scanners, this
00110         // side is usually tilted upward.
00111         // This information is part of the processing flags.
00112         bool isRearMirrorSide();
00113 
00114         // Returns true if the scan was scanned with the front mirror side. In 8-layer scanners, this
00115         // side is usually tilted downward.
00116         // This information is part of the processing flags.
00117         bool isFrontMirrorSide();
00118 
00119         // Returns the angle by which the laser beam is tilted (pitched) in [rad].
00120         //
00121         // Returns the actual angle by which the laser beam is pitched up
00122         // (negative angles) or down (positive angles) if this was an 8L
00123         // scanner. The angle is measured relatively to the sensor's
00124         // x-y-plane at a horizontal view angle of zero degree.
00125         //
00126         // Watch out: If this angle is nonzero, the actual beam tilt
00127         // changes with the horizontal angle. The formula to obtain the
00128         // actual pitch angle \f$\theta\f$ from the beam tilt \f$\beta\f$
00129         // at horizontal angle \f$\psi\f$ is
00130         // \f[
00131         // \theta = \beta\sqrt{2}\sin\left(\frac{\pi}{4}-\frac{\psi}{2}\right)
00132         // \f]
00133         //
00134         // or, written in C++ code,
00135         //   currentBeamTilt = getBeamTilt() * std::sqrt(2) * std::sin(0.25*::PI - 0.5*hAngle)
00136         double getBeamTilt() const { return m_beamTilt; }
00137 
00138         // Set the beam tilt of this scanner in radians.
00139         void setBeamTilt(double tilt);
00140 
00141         // Get the flags of the single scan belonging to this scanner info.
00142         UINT32 getScanFlags() const { return m_scanFlags; }
00143         
00144         // Set the flags of the single scan belonging to this scanner info.
00145         void setScanFlags(UINT32 flags) { m_scanFlags = flags; }
00146 
00147         // Mounting Position relative to vehicle reference point.
00148         //
00149         // All angle values in radians, and normalized to  [-pi, pi[
00150         //
00151         // All distance values in [m]
00152         //
00153         const Position3D& getMountingPosition() const { return m_mountingPosition; }
00154         void setMountingPosition(const Position3D& v) { m_mountingPosition = v; }
00155 
00156         // Get the scanner's horizontal resolution.
00157         //
00158         // For each element in the returned vector, the \c first value is
00159         // the start angle in radians. The \c second value is the
00160         // horizontal angle resolution from the start angle onwards in
00161         // radians. The returned vector of resolutions has at most 8
00162         // elements, but it might have less elements.
00163         //
00164 //      const ResolutionMap& getResolutionMap() const { return m_resolutionMap; }
00165 
00166         // Set the scanner's horizontal resolution.
00167         //
00168         // For each element, \c first is the start angle [rad] and \c
00169         // second is the horizontal angle resolution [rad]. This vector
00170         // must not have more than 8 elements, but it might have less
00171         // elements.
00172         //
00173         // Elements at the end which are all-zero will be removed in the
00174         // internally stored ResolutionMap so that only the non-zero
00175         // elements will be returned on getResolutionMap().
00176         //
00177 //      void setResolutionMap(const ResolutionMap& m);
00178 
00179         // Returns the ScannerProperties which belong to the laserscanner
00180         // type of this object.
00181         //
00182         // If an unknown or unimplemented scanner type was set during
00183         // setScannerType(), the returned ScannerProperties object has its
00184         // values set to its defaults (NaN and zero).
00185         //
00186         //
00187 //      const ScannerProperties& getScannerProperties() const;
00188 
00190 //      bool isGroundLabeled()          const;
00191 //      bool isDirtLabeled()            const;
00192 //      bool isRainLabeled()            const;
00193 //      bool isCoverageLabeled()        const;
00194 //      bool isBackgroundLabeled()      const;
00195 //      bool isReflectorLabeled()       const;
00196 //      bool isUpsideDown()                     const;
00197 //      bool isRearMirrorSide()         const;
00198 
00199 
00200 private:
00202 //      void updateScannerProperties();
00203 
00206 //      void truncateResolutionMap();
00207 
00209 //      void checkLegalBeamTilt();
00210 
00211 private:
00212         UINT8 m_deviceID;
00213         UINT8 m_scannerType;
00214         UINT16 m_scanNumber;
00215 //      UINT32 m_scannerStatus;
00216         double m_startAngle;
00217         double m_endAngle;
00218 //      float m_syncAngle;
00219         UINT16 m_processingFlags;
00220 
00222         Time m_scanStartTime;
00224         Time m_scanEndTime;
00225 
00228 //      boost::posix_time::ptime m_scanStartDeviceTime;
00229 
00232 //      boost::posix_time::ptime m_scanEndDeviceTime;
00233 
00235         double m_scanFrequency;
00237         double m_beamTilt;
00239         UINT32 m_scanFlags;
00240 
00241         Position3D m_mountingPosition;
00242 
00244 //      ResolutionMap m_resolutionMap;
00245 
00247 //      boost::shared_ptr<ScannerProperties> m_scannerProperties;
00248 };
00249 
00250 }       // namespace datatypes
00251 
00252 #endif // SCANNERINFO_HPP


libsick_ldmrs
Author(s): SICK AG , Martin Günther , Jochen Sprickerhof
autogenerated on Wed Jun 14 2017 04:04:50