SensorCaptureThread.h
Go to the documentation of this file.
1 /*
2 Copyright (c) 2010-2016, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
3 All rights reserved.
4 
5 Redistribution and use in source and binary forms, with or without
6 modification, are permitted provided that the following conditions are met:
7  * Redistributions of source code must retain the above copyright
8  notice, this list of conditions and the following disclaimer.
9  * Redistributions in binary form must reproduce the above copyright
10  notice, this list of conditions and the following disclaimer in the
11  documentation and/or other materials provided with the distribution.
12  * Neither the name of the Universite de Sherbrooke nor the
13  names of its contributors may be used to endorse or promote products
14  derived from this software without specific prior written permission.
15 
16 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
17 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
18 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
19 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
20 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
21 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
22 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
23 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
24 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
25 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26 */
27 
28 #pragma once
29 
30 #include "rtabmap/core/rtabmap_core_export.h" // DLL export/import defines
31 
33 #include <rtabmap/core/Transform.h>
36 
37 namespace clams
38 {
39 class DiscreteDepthDistortionModel;
40 }
41 
42 namespace rtabmap
43 {
44 
45 class Camera;
46 class Lidar;
47 class SensorCapture;
48 class SensorCaptureInfo;
49 class SensorData;
50 class StereoDense;
51 class IMUFilter;
52 class Feature2D;
53 
58 class RTABMAP_CORE_EXPORT SensorCaptureThread :
59  public UThread,
60  public UEventsSender
61 {
62 public:
63  // ownership transferred
65  Camera * camera,
66  const ParametersMap & parameters = ParametersMap());
74  Camera * camera,
75  SensorCapture * odomSensor,
76  const Transform & extrinsics,
77  double poseTimeOffset = 0.0,
78  float poseScaleFactor = 1.0f,
79  double poseWaitTime = 0.1,
80  const ParametersMap & parameters = ParametersMap());
85  Lidar * lidar,
86  const ParametersMap & parameters = ParametersMap());
92  Lidar * lidar,
93  Camera * camera,
94  const ParametersMap & parameters = ParametersMap());
100  Lidar * lidar,
101  SensorCapture * odomSensor,
102  double poseTimeOffset = 0.0,
103  float poseScaleFactor = 1.0f,
104  double poseWaitTime = 0.1,
105  const ParametersMap & parameters = ParametersMap());
113  Lidar * lidar,
114  Camera * camera,
115  SensorCapture * odomSensor,
116  const Transform & extrinsics,
117  double poseTimeOffset = 0.0,
118  float poseScaleFactor = 1.0f,
119  double poseWaitTime = 0.1,
120  const ParametersMap & parameters = ParametersMap());
121  virtual ~SensorCaptureThread();
122 
123  void setMirroringEnabled(bool enabled) {_mirroring = enabled;}
124  void setStereoExposureCompensation(bool enabled) {_stereoExposureCompensation = enabled;}
125  void setColorOnly(bool colorOnly) {_colorOnly = colorOnly;}
126  void setImageDecimation(int decimation) {_imageDecimation = decimation;}
127  void setHistogramMethod(int histogramMethod) {_histogramMethod = histogramMethod;}
128  void setStereoToDepth(bool enabled) {_stereoToDepth = enabled;}
129  void setFrameRate(float frameRate);
130  RTABMAP_DEPRECATED void setImageRate(float frameRate) {setFrameRate(frameRate);}
131  void setDistortionModel(const std::string & path);
132  void setOdomAsGroundTruth(bool enabled) {_odomAsGt = enabled;}
133  void enableBilateralFiltering(float sigmaS, float sigmaR);
134  void disableBilateralFiltering() {_bilateralFiltering = false;}
135  void enableIMUFiltering(int filteringStrategy=1, const ParametersMap & parameters = ParametersMap(), bool baseFrameConversion = false);
136  void disableIMUFiltering();
137  void enableFeatureDetection(const ParametersMap & parameters = ParametersMap());
138  void disableFeatureDetection();
139 
140  // Use new version of this function with groundNormalsUp=0.8 for forceGroundNormalsUp=True and groundNormalsUp=0.0 for forceGroundNormalsUp=False.
141  RTABMAP_DEPRECATED void setScanParameters(
142  bool fromDepth,
143  int downsampleStep, // decimation of the depth image in case the scan is from depth image
144  float rangeMin,
145  float rangeMax,
146  float voxelSize,
147  int normalsK,
148  float normalsRadius,
149  bool forceGroundNormalsUp,
150  bool deskewing);
151  void setScanParameters(
152  bool fromDepth,
153  int downsampleStep=1, // decimation of the depth image in case the scan is from depth image
154  float rangeMin=0.0f,
155  float rangeMax=0.0f,
156  float voxelSize = 0.0f,
157  int normalsK = 0,
158  float normalsRadius = 0.0f,
159  float groundNormalsUp = 0.0f,
160  bool deskewing = false);
161 
162  void postUpdate(SensorData * data, SensorCaptureInfo * info = 0) const;
163 
164  //getters
165  bool isPaused() const {return !this->isRunning();}
166  bool isCapturing() const {return this->isRunning();}
167  bool odomProvided() const;
168 
169  Camera * camera() {return _camera;} // return null if not set, valid until CameraThread is deleted
170  SensorCapture * odomSensor() {return _odomSensor;} // return null if not set, valid until CameraThread is deleted
171  Lidar * lidar() {return _lidar;} // return null if not set, valid until CameraThread is deleted
172 
173 private:
174  virtual void mainLoopBegin();
175  virtual void mainLoop();
176  virtual void mainLoopKill();
177 
178 private:
183  bool _odomAsGt;
211 };
212 
213 //backward compatibility
215 
216 } // namespace rtabmap
rtabmap::SensorData
Definition: SensorData.h:51
rtabmap::SensorCaptureThread
Definition: SensorCaptureThread.h:58
rtabmap::SensorCaptureThread::_odomSensor
SensorCapture * _odomSensor
Definition: SensorCaptureThread.h:180
rtabmap::SensorCaptureThread::_histogramMethod
int _histogramMethod
Definition: SensorCaptureThread.h:191
rtabmap::SensorCaptureThread::isCapturing
bool isCapturing() const
Definition: SensorCaptureThread.h:166
clams::DiscreteDepthDistortionModel
Definition: discrete_depth_distortion_model.h:68
rtabmap::SensorCaptureThread::_scanRangeMax
float _scanRangeMax
Definition: SensorCaptureThread.h:197
rtabmap::SensorCaptureThread::_colorOnly
bool _colorOnly
Definition: SensorCaptureThread.h:189
rtabmap::SensorCaptureThread::_scanRangeMin
float _scanRangeMin
Definition: SensorCaptureThread.h:196
rtabmap::SensorCaptureThread::odomSensor
SensorCapture * odomSensor()
Definition: SensorCaptureThread.h:170
Camera
rtabmap::SensorCaptureThread::_bilateralSigmaS
float _bilateralSigmaS
Definition: SensorCaptureThread.h:205
rtabmap::SensorCaptureThread::_scanForceGroundNormalsUp
float _scanForceGroundNormalsUp
Definition: SensorCaptureThread.h:201
rtabmap::RTABMAP_DEPRECATED
RTABMAP_DEPRECATED(typedef SensorData Image, "rtabmap::Image class is renamed to rtabmap::SensorData, use the last one instead.")
rtabmap::CameraThread
RTABMAP_DEPRECATED typedef SensorCaptureThread CameraThread
Definition: SensorCaptureThread.h:214
rtabmap::SensorCaptureThread::disableBilateralFiltering
void disableBilateralFiltering()
Definition: SensorCaptureThread.h:134
rtabmap::SensorCaptureThread::_poseScaleFactor
float _poseScaleFactor
Definition: SensorCaptureThread.h:185
rtabmap::SensorCaptureThread::setColorOnly
void setColorOnly(bool colorOnly)
Definition: SensorCaptureThread.h:125
Transform.h
rtabmap::SensorCaptureThread::_poseTimeOffset
double _poseTimeOffset
Definition: SensorCaptureThread.h:184
rtabmap::ParametersMap
std::map< std::string, std::string > ParametersMap
Definition: Parameters.h:43
rtabmap::SensorCaptureThread::_featureDetector
Feature2D * _featureDetector
Definition: SensorCaptureThread.h:209
rtabmap::SensorCaptureThread::_stereoToDepth
bool _stereoToDepth
Definition: SensorCaptureThread.h:192
rtabmap::SensorCaptureThread::_imuBaseFrameConversion
bool _imuBaseFrameConversion
Definition: SensorCaptureThread.h:208
rtabmap::SensorCaptureThread::_camera
Camera * _camera
Definition: SensorCaptureThread.h:179
Parameters.h
rtabmap::SensorCaptureInfo
Definition: SensorCaptureInfo.h:36
rtabmap::SensorCaptureThread::lidar
Lidar * lidar()
Definition: SensorCaptureThread.h:171
rtabmap::SensorCaptureThread::_depthAsMask
bool _depthAsMask
Definition: SensorCaptureThread.h:210
rtabmap::SensorCaptureThread::_mirroring
bool _mirroring
Definition: SensorCaptureThread.h:187
rtabmap::IMUFilter
Definition: IMUFilter.h:37
rtabmap::SensorCaptureThread::_imageDecimation
int _imageDecimation
Definition: SensorCaptureThread.h:190
rtabmap::SensorCaptureThread::_stereoExposureCompensation
bool _stereoExposureCompensation
Definition: SensorCaptureThread.h:188
rtabmap::StereoDense
Definition: StereoDense.h:38
rtabmap::SensorCaptureThread::_scanNormalsRadius
float _scanNormalsRadius
Definition: SensorCaptureThread.h:200
rtabmap::SensorCaptureThread::setStereoExposureCompensation
void setStereoExposureCompensation(bool enabled)
Definition: SensorCaptureThread.h:124
rtabmap::SensorCaptureThread::setMirroringEnabled
void setMirroringEnabled(bool enabled)
Definition: SensorCaptureThread.h:123
rtabmap::Feature2D
Definition: Features2d.h:106
rtabmap::SensorCaptureThread::_imuFilter
IMUFilter * _imuFilter
Definition: SensorCaptureThread.h:207
rtabmap::SensorCaptureThread::_bilateralFiltering
bool _bilateralFiltering
Definition: SensorCaptureThread.h:204
rtabmap::SensorCaptureThread::setImageRate
RTABMAP_DEPRECATED void setImageRate(float frameRate)
Definition: SensorCaptureThread.h:130
rtabmap::Camera
Definition: Camera.h:43
rtabmap::SensorCaptureThread::setStereoToDepth
void setStereoToDepth(bool enabled)
Definition: SensorCaptureThread.h:128
rtabmap::SensorCaptureThread::_scanFromDepth
bool _scanFromDepth
Definition: SensorCaptureThread.h:194
rtabmap::SensorCapture
Definition: SensorCapture.h:49
rtabmap::SensorCaptureThread::_odomAsGt
bool _odomAsGt
Definition: SensorCaptureThread.h:183
clams
Definition: discrete_depth_distortion_model.h:41
f
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
UEventsSender.h
rtabmap::Transform
Definition: Transform.h:41
UThread
Definition: UThread.h:86
rtabmap::SensorCaptureThread::_scanVoxelSize
float _scanVoxelSize
Definition: SensorCaptureThread.h:198
rtabmap::SensorCaptureThread::_scanDeskewing
bool _scanDeskewing
Definition: SensorCaptureThread.h:193
rtabmap::SensorCaptureThread::_scanDownsampleStep
int _scanDownsampleStep
Definition: SensorCaptureThread.h:195
rtabmap::SensorCaptureThread::_lidar
Lidar * _lidar
Definition: SensorCaptureThread.h:181
rtabmap::SensorCaptureThread::_scanNormalsK
int _scanNormalsK
Definition: SensorCaptureThread.h:199
rtabmap::SensorCaptureThread::_stereoDense
StereoDense * _stereoDense
Definition: SensorCaptureThread.h:202
rtabmap::SensorCaptureThread::_extrinsicsOdomToCamera
Transform _extrinsicsOdomToCamera
Definition: SensorCaptureThread.h:182
rtabmap::SensorCaptureThread::setImageDecimation
void setImageDecimation(int decimation)
Definition: SensorCaptureThread.h:126
camera
Camera camera(Pose3(Rot3().retract(Vector3(0.1, 0.2, 0.3)), Point3(0, 5, 0)), Cal3Bundler0(1, 0, 0))
UThread.h
rtabmap::SensorCaptureThread::_poseWaitTime
double _poseWaitTime
Definition: SensorCaptureThread.h:186
rtabmap::Lidar
Definition: Lidar.h:40
rtabmap::SensorCaptureThread::_distortionModel
clams::DiscreteDepthDistortionModel * _distortionModel
Definition: SensorCaptureThread.h:203
rtabmap::SensorCaptureThread::camera
Camera * camera()
Definition: SensorCaptureThread.h:169
rtabmap
Definition: CameraARCore.cpp:35
rtabmap::SensorCaptureThread::setHistogramMethod
void setHistogramMethod(int histogramMethod)
Definition: SensorCaptureThread.h:127
rtabmap::SensorCaptureThread::isPaused
bool isPaused() const
Definition: SensorCaptureThread.h:165
rtabmap::SensorCaptureThread::_bilateralSigmaR
float _bilateralSigmaR
Definition: SensorCaptureThread.h:206
UEventsSender
Definition: UEventsSender.h:15
rtabmap::SensorCaptureThread::setOdomAsGroundTruth
void setOdomAsGroundTruth(bool enabled)
Definition: SensorCaptureThread.h:132


rtabmap
Author(s): Mathieu Labbe
autogenerated on Mon Jul 1 2024 02:42:33