Main class for orsens camera. More...
#include <orsens.h>
Public Types | |
| enum | CaptureMode { CAPTURE_DEPTH_ONLY = 0, CAPTURE_LEFT_ONLY, CAPTURE_DEPTH_LEFT, CAPTURE_LEFT_RIGHT } |
Public Member Functions | |
| float | directionToImagePoint (uint16_t x, uint16_t y) |
| float | directionToImageRect (Rect rect) |
| uint16_t | disp2dist (uint8_t disp) |
| uint8_t | disparityAtImagePoint (uint16_t x, uint16_t y) |
| uint8_t | dist2disp (uint16_t dist) |
| Scalar | dist2rgb (uint16_t dist) |
| uint16_t | distanceToImagePoint (uint16_t x, uint16_t y) |
| uint16_t | distanceToImageRect (Rect rect) |
| bool | filterDisp (uint16_t maxSpeckleSize=1000, uint8_t newVal=0) |
| CameraParameters | getARCameraParametres (uint8_t camera_num) |
| Size | getColorSize () |
| Mat | getDepth (bool depth8=false) |
| Size | getDepthSize () |
| Mat | getDisp (bool colored=false) |
| ScenePoint | getFarestPoint (uint16_t width=100) |
| std::vector< Human > | getHumans () |
| Mat | getLeft (bool gray=false) |
| vector< Marker > | getMarkers (uint8_t camera_num=0, float marker_size=0.04) |
| uint16_t | getMaxDistance () |
| uint16_t | getMinDistance () |
| bool | getNearestHumanBiometrics (Human &human) |
| Mat | getPointCloud () |
| uint8_t | getRate () |
| Mat | getRight () |
| Mat | getSceneGrid (vector< float > cols, vector< float > rows, int dist_th=3000, float occ_th=0.1, float pts_th=0.01) |
| SceneInfo | getSceneInfo (bool nearest_obstacle=true, bool nearest_point=true) |
| bool | grabSensorData () |
| int32_t | maxWorldX (uint16_t x) |
| int32_t | maxWorldY (uint16_t y) |
| Orsens () | |
| bool | removeFloor () |
| void | setRoi (Rect) |
| 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, bool compress_color=false, bool compress_depth=false, float fov=60.0, uint16_t baseline=60) |
| bool | stop () |
| Point3i | worldPointAtImagePoint (uint16_t x, uint16_t y) |
| Point3f | worldPointAtImagePointM (uint16_t x, uint16_t y) |
| ~Orsens () | |
Static Public Member Functions | |
| static CaptureMode | captureModeFromString (const std::string &str) |
Public Attributes | |
| CaptureMode | capture_mode_ |
Private Member Functions | |
| bool | makeDepth () |
| bool | makeGray () |
| bool | makeNearestDistance () |
| bool | makeNearestObstacle () |
| bool | makeNearestPoint () |
| bool | segmentFloor () |
Private Attributes | |
| uint16_t | baseline_ |
| uint16_t | color_height_ |
| uint8_t | color_rate_ |
| uint16_t | color_width_ |
| uint16_t | cx_ |
| uint16_t | cy_ |
| string | data_path_ |
| Mat | depth8_ |
| Mat | depth_ |
| uint16_t | depth_height_ |
| uint8_t | depth_rate_ |
| uint16_t | depth_width_ |
| Mat | disp_ |
| Mat | disp_raw_ |
| Mat | disp_raw_prev_ |
| Mat | disp_src_ |
| uint16_t | focal_ |
| float | fov_ |
| bool | got_depth_ |
| bool | got_gray_ |
| bool | got_seg_mask |
| std::vector< Human > | humans_ |
| Mat | left_ |
| Mat | left_gray_ |
| uint16_t | left_height_ |
| uint16_t | left_width_ |
| uint16_t | max_distance_ |
| uint16_t | min_distance_ |
| Mat | point_cloud_ |
| Mat | right_ |
| Mat | right_gray_ |
| Rect | roi_ |
| SceneInfo | scene_info_ |
| Mat | segmentation_mask_ |
| uint16_t | zdtable_ [DISPARITY_COUNT] |
Static Private Attributes | |
| static const int | DISPARITY_COUNT = 256 |
| static const int | NO_ANGLE = 361 |
| static const int | NO_DISTANCE = 0 |
| enum Orsens::CaptureMode |
| Orsens::Orsens | ( | ) | [inline] |
| Orsens::~Orsens | ( | ) | [inline] |
| static CaptureMode Orsens::captureModeFromString | ( | const std::string & | str | ) | [static] |
use this if you want to set the value of CaptureMode in ros launch
possible values: depth_only, left_only, depth_left and left_right
| float Orsens::directionToImagePoint | ( | uint16_t | x, |
| uint16_t | y | ||
| ) |
returs directon to image point
| float Orsens::directionToImageRect | ( | Rect | rect | ) |
returns direction to image rectangle
| uint16_t Orsens::disp2dist | ( | uint8_t | disp | ) |
returns distance for given disparity
| disp | disparity (0-255) |
| uint8_t Orsens::disparityAtImagePoint | ( | uint16_t | x, |
| uint16_t | y | ||
| ) |
returns disparity at image point
| uint8_t Orsens::dist2disp | ( | uint16_t | dist | ) |
returns diparity for given distance
| dist | distance in millimetres |
| Scalar Orsens::dist2rgb | ( | uint16_t | dist | ) |
returns rgb value for given distance
| dist | distance in millimetres |
| uint16_t Orsens::distanceToImagePoint | ( | uint16_t | x, |
| uint16_t | y | ||
| ) |
returns distance to image point in millimetres
| uint16_t Orsens::distanceToImageRect | ( | Rect | rect | ) |
returns distance to image rectangle in millimetres
| bool Orsens::filterDisp | ( | uint16_t | maxSpeckleSize = 1000, |
| uint8_t | newVal = 0 |
||
| ) |
removes speckles
| maxSpeckleSize | The maximum speckle size to consider it a speckle |
| newVal | The disparity value used to paint-off the speckles |
| CameraParameters Orsens::getARCameraParametres | ( | uint8_t | camera_num | ) |
returns camera parametres used by aruco
| camera_num | 0 - left camera, 1 - right camera |
| Size Orsens::getColorSize | ( | ) |
returns size of the left image
| Mat Orsens::getDepth | ( | bool | depth8 = false | ) |
returns depth map
| depth8 | if set depth is scaled to fit 8 bit for visualizaton |
| Size Orsens::getDepthSize | ( | ) |
returns size of the depth image
| Mat Orsens::getDisp | ( | bool | colored = false | ) |
returns disparity map
| colored | if set disp is colored for visualization |
| ScenePoint Orsens::getFarestPoint | ( | uint16_t | width = 100 | ) |
returns farest point
| width | x-zone width |
| std::vector<Human> Orsens::getHumans | ( | ) |
returns vector of all humans in the scene
| Mat Orsens::getLeft | ( | bool | gray = false | ) |
returns rgb image from left camera
| gray | if set returns gray image |
| vector<Marker> Orsens::getMarkers | ( | uint8_t | camera_num = 0, |
| float | marker_size = 0.04 |
||
| ) |
returns aruco markers, for more information see ArUco documentation
| camera_num | 0 - left camera, 1 - right camera |
| marker_size | size of the marker side expressed in meters |
| uint16_t Orsens::getMaxDistance | ( | ) |
returns maximum possible distance
| uint16_t Orsens::getMinDistance | ( | ) |
returns minimun possible distance camera able to measure
| bool Orsens::getNearestHumanBiometrics | ( | Human & | human | ) |
estimates age and gender of nearest human
| human | output value |
| Mat Orsens::getPointCloud | ( | ) |
returns point cloud
| uint8_t Orsens::getRate | ( | ) |
returns depth rate
| Mat Orsens::getRight | ( | ) |
returns rgb image from right camera
| Mat Orsens::getSceneGrid | ( | vector< float > | cols, |
| vector< float > | rows, | ||
| int | dist_th = 3000, |
||
| float | occ_th = 0.1, |
||
| float | pts_th = 0.01 |
||
| ) |
returns grid with given cols and rows
| cols | vector of column widths |
| rows | vector of row widths |
| dist_th | distance threshold |
| occ_th | occupancy threshold |
| pts_th | minimun number of points with distances less than dist_th in % in each cell to consider it as filled |
| SceneInfo Orsens::getSceneInfo | ( | bool | nearest_obstacle = true, |
| bool | nearest_point = true |
||
| ) |
returns nearest distance, nearest point(if nearest_point is set to true) and nearest obstacle(if nearest_obstacle is set to true)
| nearest_obstacle | if set estimates nearest obstacle information |
| nearest_point | if set estimates nearest point information |
| bool Orsens::grabSensorData | ( | ) |
grab current images from sensor
| bool Orsens::makeDepth | ( | ) | [private] |
| bool Orsens::makeGray | ( | ) | [private] |
| bool Orsens::makeNearestDistance | ( | ) | [private] |
| bool Orsens::makeNearestObstacle | ( | ) | [private] |
| bool Orsens::makeNearestPoint | ( | ) | [private] |
| int32_t Orsens::maxWorldX | ( | uint16_t | x | ) |
| int32_t Orsens::maxWorldY | ( | uint16_t | y | ) |
| bool Orsens::removeFloor | ( | ) |
removes floor points
| bool Orsens::segmentFloor | ( | ) | [private] |
| void Orsens::setRoi | ( | Rect | ) |
sets region of interest
| Rect | region of intrest; default: whole image |
| bool Orsens::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, |
||
| bool | compress_color = false, |
||
| bool | compress_depth = false, |
||
| float | fov = 60.0, |
||
| uint16_t | baseline = 60 |
||
| ) |
start capturing
| bool Orsens::stop | ( | ) |
stop capturing
| Point3i Orsens::worldPointAtImagePoint | ( | uint16_t | x, |
| uint16_t | y | ||
| ) |
returns world point at image point in millimetres
| Point3f Orsens::worldPointAtImagePointM | ( | uint16_t | x, |
| uint16_t | y | ||
| ) |
returns world point at image point in metres
uint16_t Orsens::baseline_ [private] |
uint16_t Orsens::color_height_ [private] |
uint8_t Orsens::color_rate_ [private] |
uint16_t Orsens::color_width_ [private] |
uint16_t Orsens::cx_ [private] |
uint16_t Orsens::cy_ [private] |
string Orsens::data_path_ [private] |
Mat Orsens::depth8_ [private] |
Mat Orsens::depth_ [private] |
uint16_t Orsens::depth_height_ [private] |
uint8_t Orsens::depth_rate_ [private] |
uint16_t Orsens::depth_width_ [private] |
Mat Orsens::disp_ [private] |
Mat Orsens::disp_raw_ [private] |
Mat Orsens::disp_raw_prev_ [private] |
Mat Orsens::disp_src_ [private] |
const int Orsens::DISPARITY_COUNT = 256 [static, private] |
uint16_t Orsens::focal_ [private] |
float Orsens::fov_ [private] |
bool Orsens::got_depth_ [private] |
bool Orsens::got_gray_ [private] |
bool Orsens::got_seg_mask [private] |
std::vector<Human> Orsens::humans_ [private] |
Mat Orsens::left_ [private] |
Mat Orsens::left_gray_ [private] |
uint16_t Orsens::left_height_ [private] |
uint16_t Orsens::left_width_ [private] |
uint16_t Orsens::max_distance_ [private] |
uint16_t Orsens::min_distance_ [private] |
const int Orsens::NO_ANGLE = 361 [static, private] |
const int Orsens::NO_DISTANCE = 0 [static, private] |
Mat Orsens::point_cloud_ [private] |
Mat Orsens::right_ [private] |
Mat Orsens::right_gray_ [private] |
Rect Orsens::roi_ [private] |
SceneInfo Orsens::scene_info_ [private] |
Mat Orsens::segmentation_mask_ [private] |
uint16_t Orsens::zdtable_[DISPARITY_COUNT] [private] |