CameraDepthAI.h
Go to the documentation of this file.
1 /*
2 Copyright (c) 2010-2021, 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 
31 #include "rtabmap/core/Camera.h"
32 #include "rtabmap/core/Version.h"
33 
34 #ifdef RTABMAP_DEPTHAI
35 #ifndef DEPTHAI_OPENCV_SUPPORT
36 #define DEPTHAI_OPENCV_SUPPORT
37 #endif
38 #include <depthai/depthai.hpp>
39 #endif
40 
41 namespace rtabmap
42 {
43 
44 class RTABMAP_CORE_EXPORT CameraDepthAI :
45  public Camera
46 {
47 public:
48  static bool available();
49 
50 public:
52  const std::string & mxidOrName = "",
53  int resolution = 1, // 0=720p, 1=800p, 2=400p
54  float imageRate=0.0f,
55  const Transform & localTransform = Transform::getIdentity());
56  virtual ~CameraDepthAI();
57 
58  void setOutputMode(int outputMode = 0);
59  void setDepthProfile(int confThreshold = 200, int lrcThreshold = 5);
60  void setExtendedDisparity(bool extendedDisparity);
61  void setSubpixelMode(bool enabled, int fractionalBits = 3);
62  void setCompanding(bool enabled, int width=96);
63  void setRectification(bool useSpecTranslation, float alphaScaling = 0.0f, bool enabled=true);
64  void setIMU(bool imuPublished, bool publishInterIMU);
65  void setIrIntensity(float dotIntensity = 0.0f, float floodIntensity = 0.0f);
66  void setDetectFeatures(int detectFeatures = 0);
67  void setBlobPath(const std::string & blobPath);
68  void setGFTTDetector(bool useHarrisDetector = false, float minDistance = 7.0f, int numTargetFeatures = 1000);
69  void setSuperPointDetector(float threshold = 0.01f, bool nms = true, int nmsRadius = 4);
70 
71  virtual bool init(const std::string & calibrationFolder = ".", const std::string & cameraName = "");
72  virtual bool isCalibrated() const;
73  virtual std::string getSerial() const;
74 
75 protected:
76  virtual SensorData captureImage(SensorCaptureInfo * info = 0);
77 
78 private:
79 #ifdef RTABMAP_DEPTHAI
80  StereoCameraModel stereoModel_;
81  cv::Size targetSize_;
82  Transform imuLocalTransform_;
83  std::string mxidOrName_;
84  int outputMode_;
85  int confThreshold_;
86  int lrcThreshold_;
87  int resolution_;
88  bool extendedDisparity_;
89  int subpixelFractionalBits_;
90  int compandingWidth_;
91  bool useSpecTranslation_;
92  float alphaScaling_;
93  bool imagesRectified_;
94  bool imuPublished_;
95  bool publishInterIMU_;
96  float dotIntensity_;
97  float floodIntensity_;
98  int detectFeatures_;
99  bool useHarrisDetector_;
100  float minDistance_;
101  int numTargetFeatures_;
102  float threshold_;
103  bool nms_;
104  int nmsRadius_;
105  std::string blobPath_;
106  std::shared_ptr<dai::Device> device_;
107  std::shared_ptr<dai::DataOutputQueue> cameraQueue_;
108  std::map<double, cv::Vec3f> accBuffer_;
109  std::map<double, cv::Vec3f> gyroBuffer_;
110  UMutex imuMutex_;
111 #endif
112 };
113 
114 
115 } // namespace rtabmap
rtabmap::SensorData
Definition: SensorData.h:51
rtabmap::StereoCameraModel
Definition: StereoCameraModel.h:35
rtabmap::CameraDepthAI
Definition: CameraDepthAI.h:44
rtabmap::Transform::getIdentity
static Transform getIdentity()
Definition: Transform.cpp:411
threshold_
Index threshold_
rtabmap::SensorCaptureInfo
Definition: SensorCaptureInfo.h:36
UMutex
Definition: UMutex.h:54
info
else if n * info
StereoCameraModel.h
rtabmap::Camera
Definition: Camera.h:43
f
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
rtabmap_netvlad.init
def init(descriptorDim)
Definition: rtabmap_netvlad.py:30
rtabmap::Transform
Definition: Transform.h:41
Camera.h
rtabmap
Definition: CameraARCore.cpp:35


rtabmap
Author(s): Mathieu Labbe
autogenerated on Thu Jul 25 2024 02:50:07