Public Types | Public Member Functions | Static Public Member Functions | Public Attributes | Private Member Functions | Private Attributes | Static Private Attributes
Orsens Class Reference

Main class for orsens camera. More...

#include <orsens.h>

List of all members.

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< HumangetHumans ()
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< Humanhumans_
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

Detailed Description

Main class for orsens camera.

Definition at line 162 of file orsens.h.


Member Enumeration Documentation

Enumerator:
CAPTURE_DEPTH_ONLY 
CAPTURE_LEFT_ONLY 
CAPTURE_DEPTH_LEFT 
CAPTURE_LEFT_RIGHT 

Definition at line 224 of file orsens.h.


Constructor & Destructor Documentation

Orsens::Orsens ( ) [inline]

empty constructor

Definition at line 221 of file orsens.h.

Orsens::~Orsens ( ) [inline]

Definition at line 222 of file orsens.h.


Member Function Documentation

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

Parameters:
dispdisparity (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

Parameters:
distdistance in millimetres
Scalar Orsens::dist2rgb ( uint16_t  dist)

returns rgb value for given distance

Parameters:
distdistance 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

Parameters:
maxSpeckleSizeThe maximum speckle size to consider it a speckle
newValThe disparity value used to paint-off the speckles
CameraParameters Orsens::getARCameraParametres ( uint8_t  camera_num)

returns camera parametres used by aruco

Parameters:
camera_num0 - left camera, 1 - right camera

returns size of the left image

Mat Orsens::getDepth ( bool  depth8 = false)

returns depth map

Parameters:
depth8if set depth is scaled to fit 8 bit for visualizaton

returns size of the depth image

Mat Orsens::getDisp ( bool  colored = false)

returns disparity map

Parameters:
coloredif set disp is colored for visualization
ScenePoint Orsens::getFarestPoint ( uint16_t  width = 100)

returns farest point

Parameters:
widthx-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

Parameters:
grayif 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

Parameters:
camera_num0 - left camera, 1 - right camera
marker_sizesize 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

estimates age and gender of nearest human

Parameters:
humanoutput value

returns point cloud

uint8_t Orsens::getRate ( )

returns depth rate

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

Parameters:
colsvector of column widths
rowsvector of row widths
dist_thdistance threshold
occ_thoccupancy threshold
pts_thminimun 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)

Parameters:
nearest_obstacleif set estimates nearest obstacle information
nearest_pointif set estimates nearest point information

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)

removes floor points

bool Orsens::segmentFloor ( ) [private]
void Orsens::setRoi ( Rect  )

sets region of interest

Parameters:
Rectregion 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


Member Data Documentation

uint16_t Orsens::baseline_ [private]

Definition at line 203 of file orsens.h.

capture mode: only depth image, only left image, depth and left images or left and right images

Definition at line 230 of file orsens.h.

uint16_t Orsens::color_height_ [private]

Definition at line 173 of file orsens.h.

uint8_t Orsens::color_rate_ [private]

Definition at line 174 of file orsens.h.

uint16_t Orsens::color_width_ [private]

Definition at line 172 of file orsens.h.

uint16_t Orsens::cx_ [private]

Definition at line 201 of file orsens.h.

uint16_t Orsens::cy_ [private]

Definition at line 202 of file orsens.h.

string Orsens::data_path_ [private]

Definition at line 170 of file orsens.h.

Mat Orsens::depth8_ [private]

Definition at line 185 of file orsens.h.

Mat Orsens::depth_ [private]

Definition at line 185 of file orsens.h.

uint16_t Orsens::depth_height_ [private]

Definition at line 176 of file orsens.h.

uint8_t Orsens::depth_rate_ [private]

Definition at line 177 of file orsens.h.

uint16_t Orsens::depth_width_ [private]

Definition at line 175 of file orsens.h.

Mat Orsens::disp_ [private]

Definition at line 185 of file orsens.h.

Mat Orsens::disp_raw_ [private]

Definition at line 185 of file orsens.h.

Mat Orsens::disp_raw_prev_ [private]

Definition at line 185 of file orsens.h.

Mat Orsens::disp_src_ [private]

Definition at line 185 of file orsens.h.

const int Orsens::DISPARITY_COUNT = 256 [static, private]

Definition at line 196 of file orsens.h.

uint16_t Orsens::focal_ [private]

Definition at line 204 of file orsens.h.

float Orsens::fov_ [private]

Definition at line 205 of file orsens.h.

bool Orsens::got_depth_ [private]

Definition at line 190 of file orsens.h.

bool Orsens::got_gray_ [private]

Definition at line 190 of file orsens.h.

bool Orsens::got_seg_mask [private]

Definition at line 190 of file orsens.h.

std::vector<Human> Orsens::humans_ [private]

Definition at line 208 of file orsens.h.

Mat Orsens::left_ [private]

Definition at line 183 of file orsens.h.

Mat Orsens::left_gray_ [private]

Definition at line 184 of file orsens.h.

uint16_t Orsens::left_height_ [private]

Definition at line 180 of file orsens.h.

uint16_t Orsens::left_width_ [private]

Definition at line 179 of file orsens.h.

uint16_t Orsens::max_distance_ [private]

Definition at line 200 of file orsens.h.

uint16_t Orsens::min_distance_ [private]

Definition at line 199 of file orsens.h.

const int Orsens::NO_ANGLE = 361 [static, private]

Definition at line 168 of file orsens.h.

const int Orsens::NO_DISTANCE = 0 [static, private]

Definition at line 167 of file orsens.h.

Mat Orsens::point_cloud_ [private]

Definition at line 186 of file orsens.h.

Mat Orsens::right_ [private]

Definition at line 183 of file orsens.h.

Mat Orsens::right_gray_ [private]

Definition at line 184 of file orsens.h.

Rect Orsens::roi_ [private]

Definition at line 193 of file orsens.h.

Definition at line 209 of file orsens.h.

Definition at line 187 of file orsens.h.

uint16_t Orsens::zdtable_[DISPARITY_COUNT] [private]

Definition at line 197 of file orsens.h.


The documentation for this class was generated from the following file:


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