orsens.h
Go to the documentation of this file.
00001 
00077 #ifndef ORSENS_H_INCLUDED
00078 #define ORSENS_H_INCLUDED
00079 
00080 #define NOMINMAX
00081 
00082 #include <stdint.h>
00083 #include <stdio.h>
00084 
00085 #include "orcv.h"
00086 #include "orar.h"
00087 
00091 struct ScenePoint
00092 {
00093     Point2i pt_image;
00094     Point3f pt_world;
00095 };
00096 
00100 struct SceneObject
00101 {
00103     uint16_t dist;
00105     double angle;
00106 
00108     Rect bounding_rect;
00110     Point2i centre;
00112     Point3f centre_world;
00113 };
00114 
00118 struct Human : SceneObject
00119 {
00121     string gender;
00123     uint8_t age;
00124 
00126     Rect face_rect;
00128     Point left_eye_pos;
00130     Point right_eye_pos;
00131 };
00132 
00136 struct Obstacle : SceneObject
00137 {
00139     Point3f min_pt_world;
00141     Point3f max_pt_world;
00142 };
00143 
00147 struct SceneInfo
00148 {
00150     uint16_t nearest_distance;
00152     uint8_t nearest_disp;
00154     ScenePoint nearest_point;
00156     Obstacle nearest_obstacle;
00157 };
00158 
00162 class Orsens
00163 {
00164 
00165 private:
00166 
00167     static const int NO_DISTANCE = 0;
00168     static const int NO_ANGLE = 361;
00169 
00170     string data_path_;
00171 
00172     uint16_t color_width_;
00173     uint16_t color_height_;
00174     uint8_t color_rate_;
00175     uint16_t depth_width_;
00176     uint16_t depth_height_;
00177     uint8_t depth_rate_;
00178 
00179     uint16_t left_width_;
00180     uint16_t left_height_;
00181 
00182     //images
00183     Mat left_, right_;
00184     Mat left_gray_, right_gray_;
00185     Mat disp_, disp_raw_, disp_raw_prev_, disp_src_, depth_, depth8_;
00186     Mat point_cloud_;
00187     Mat segmentation_mask_;
00188 
00189     //what we've got processed
00190     bool got_gray_, got_depth_, got_seg_mask;
00191 
00192     //parametrs
00193     Rect roi_;
00194 
00195     //camera info
00196     static const int DISPARITY_COUNT = 256;
00197     uint16_t zdtable_[DISPARITY_COUNT];
00198 
00199     uint16_t min_distance_;
00200     uint16_t max_distance_;
00201     uint16_t cx_;
00202     uint16_t cy_;
00203     uint16_t baseline_;
00204     uint16_t focal_;
00205     float fov_;
00206 
00207     //scene info
00208     std::vector<Human> humans_;
00209     SceneInfo scene_info_;
00210 
00211     //processing
00212     bool makeGray();
00213     bool makeDepth();
00214     bool makeNearestDistance();
00215     bool makeNearestPoint();
00216     bool makeNearestObstacle();
00217     bool segmentFloor();
00218 
00219 public:
00221     Orsens() {};
00222     ~Orsens() {};
00223 
00224     typedef enum
00225     {
00226         CAPTURE_DEPTH_ONLY=0, CAPTURE_LEFT_ONLY, CAPTURE_DEPTH_LEFT, CAPTURE_LEFT_RIGHT,
00227     } CaptureMode;
00228 
00230     CaptureMode capture_mode_;
00231 
00237     static CaptureMode captureModeFromString(const std::string& str);
00238 
00240     bool start(CaptureMode capture_mode=CAPTURE_DEPTH_ONLY, string data_path="../../data", uint16_t color_width=640, uint16_t depth_width=640, uint8_t color_rate=15, uint8_t depth_rate=15,
00241                bool compress_color=false, bool compress_depth=false, float fov=60.0, uint16_t baseline=60);
00243     bool stop();
00244 
00245     //setting parametrs
00246 
00250     void setRoi(Rect);
00251 
00253     bool grabSensorData();
00254 
00255     //processing
00260     bool filterDisp(uint16_t maxSpeckleSize=1000, uint8_t newVal=0);
00261 
00264     bool removeFloor();
00265 
00266     //getting data
00267 
00271     Mat getLeft(bool gray=false);
00274     Mat getRight();
00278     Mat getDisp(bool colored=false);
00282     Mat getDepth(bool depth8=false);
00285     Mat getPointCloud();
00286 
00289     Size getDepthSize();
00292     Size getColorSize();
00294     uint8_t getRate();
00295 
00296     //measuring. distances are in millimetres, except functions ends with M (metres). directions in angles
00298     uint8_t disparityAtImagePoint(uint16_t x, uint16_t y);
00300     uint16_t distanceToImagePoint(uint16_t x, uint16_t y);
00302     uint16_t distanceToImageRect(Rect rect);
00304     Point3i worldPointAtImagePoint(uint16_t x, uint16_t y);
00306     Point3f worldPointAtImagePointM(uint16_t x, uint16_t y);
00308     float directionToImagePoint(uint16_t x, uint16_t y);
00310     float directionToImageRect(Rect rect);
00311 
00312 
00313     int32_t maxWorldX(uint16_t x);
00314     int32_t maxWorldY(uint16_t y);
00315 
00318     uint16_t getMinDistance();
00321     uint16_t getMaxDistance();
00322 
00323     //scene information
00328     SceneInfo getSceneInfo(bool nearest_obstacle=true, bool nearest_point=true);
00332     ScenePoint getFarestPoint(uint16_t width=100);
00340     Mat getSceneGrid(vector<float> cols, vector<float> rows, int dist_th=3000, float occ_th=0.1, float pts_th=0.01);
00341 
00342     //detection
00345     std::vector<Human> getHumans();
00349     bool getNearestHumanBiometrics(Human &human);
00350 
00351     //aruco functions
00357     vector<Marker> getMarkers(uint8_t camera_num=0, float marker_size=0.04);
00361     CameraParameters getARCameraParametres(uint8_t camera_num);
00362 
00363     //misc
00367     Scalar dist2rgb(uint16_t dist);
00371     uint8_t dist2disp(uint16_t dist);
00375     uint16_t disp2dist(uint8_t disp);
00376 };
00377 
00378 #endif // ORSENS_H_INCLUDED


orsens_ros
Author(s):
autogenerated on Sat Jun 8 2019 18:30:26