Visual Servoing Platform  version 3.6.1 under development (2024-03-28)
vpOccipitalStructure Class Reference

#include <visp3/sensor/vpOccipitalStructure.h>

Public Types

enum  vpOccipitalStructureStream { visible , depth , infrared , imu }
 

Public Member Functions

 vpOccipitalStructure ()
 
 ~vpOccipitalStructure ()
 
void acquire (vpImage< unsigned char > &gray, bool undistorted=false, double *ts=nullptr)
 
void acquire (vpImage< vpRGBa > &rgb, bool undistorted=false, double *ts=nullptr)
 
void acquire (vpImage< vpRGBa > *rgb, vpImage< vpRGBa > *depth, vpColVector *acceleration_data=nullptr, vpColVector *gyroscope_data=nullptr, bool undistorted=false, double *ts=nullptr)
 
void acquire (vpImage< unsigned char > *gray, vpImage< vpRGBa > *depth, vpColVector *acceleration_data=nullptr, vpColVector *gyroscope_data=nullptr, bool undistorted=false, double *ts=nullptr)
 
void acquire (unsigned char *const data_image, unsigned char *const data_depth, std::vector< vpColVector > *const data_pointCloud=nullptr, unsigned char *const data_infrared=nullptr, vpColVector *acceleration_data=nullptr, vpColVector *gyroscope_data=nullptr, bool undistorted=true, double *ts=nullptr)
 
void acquire (unsigned char *const data_image, unsigned char *const data_depth, std::vector< vpColVector > *const data_pointCloud, pcl::PointCloud< pcl::PointXYZ >::Ptr &pointcloud, unsigned char *const data_infrared=nullptr, vpColVector *acceleration_data=nullptr, vpColVector *gyroscope_data=nullptr, bool undistorted=true, double *ts=nullptr)
 
void acquire (unsigned char *const data_image, unsigned char *const data_depth, std::vector< vpColVector > *const data_pointCloud, pcl::PointCloud< pcl::PointXYZRGB >::Ptr &pointcloud, unsigned char *const data_infrared=nullptr, vpColVector *acceleration_data=nullptr, vpColVector *gyroscope_data=nullptr, bool undistorted=true, double *ts=nullptr)
 
void getIMUVelocity (vpColVector *imu_vel, double *ts)
 
void getIMUAcceleration (vpColVector *imu_acc, double *ts)
 
void getIMUData (vpColVector *imu_vel, vpColVector *imu_acc, double *ts=nullptr)
 
bool open (const ST::CaptureSessionSettings &settings)
 
void close ()
 
ST::StructureCoreCameraType getCameraType () const
 
ST::CaptureSessionUSBVersion getUSBVersion () const
 
std::string getSerialNumber () const
 
ST::CaptureSession & getCaptureSession ()
 
ST::CaptureSessionSettings & getCaptureSessionSettings ()
 
unsigned int getWidth (vpOccipitalStructureStream stream_type)
 
unsigned int getHeight (vpOccipitalStructureStream stream_type)
 
float getDepth (int x, int y)
 
vpPoint unprojectPoint (int row, int col)
 
vpHomogeneousMatrix getTransform (const vpOccipitalStructureStream from, const vpOccipitalStructureStream to)
 
ST::Intrinsics getIntrinsics (const vpOccipitalStructureStream stream_type) const
 
vpCameraParameters getCameraParameters (const vpOccipitalStructureStream stream_type, vpCameraParameters::vpCameraParametersProjType type=vpCameraParameters::perspectiveProjWithoutDistortion)
 
void saveDepthImageAsPointCloudMesh (std::string &filename)
 

Protected Member Functions

void getPointcloud (std::vector< vpColVector > &pointcloud)
 
void getPointcloud (pcl::PointCloud< pcl::PointXYZ >::Ptr &pointcloud)
 
void getColoredPointcloud (pcl::PointCloud< pcl::PointXYZRGB >::Ptr &pointcloud)
 

Protected Attributes

bool m_init
 
float m_invalidDepthValue
 
float m_maxZ
 
ST::CaptureSession m_captureSession
 
ST::CaptureSessionSettings m_captureSessionSettings
 
SessionDelegate m_delegate
 
vpCameraParameters m_visible_camera_parameters
 
vpCameraParameters m_depth_camera_parameters
 

Detailed Description

This class provides a wrapper over the Occipital Structure SDK library https://structure.io/developers. It allows to capture data from the Occipital Structure Core camera.

Note
Supported devices for Occipital Structure SDK 0.9:
  • Occipital Structure Core.

The usage of vpOccipitalStructure class is enabled when libStructure 3rd party is successfully installed. The following tutorials explain how to proceed:

Moreover, if Point Cloud Library (PCL) 3rd party is installed, we also propose interfaces to retrieve point cloud as pcl::PointCloud<pcl::PointXYZ> or pcl::PointCloud<pcl::PointXYZRGB> data structures.

Warning
Notice that the usage of this class requires compiler and library support for the ISO C++ 2011 standard. This support is enabled by default in ViSP when supported by the compiler. Hereafter we give an example of a CMakeLists.txt file that allows to build sample-structure-core.cpp that uses vpOccipitalStructure class.
cmake_minimum_required(VERSION 3.5)
project(sample)
find_package(VISP REQUIRED)
include_directories(${VISP_INCLUDE_DIRS})
add_executable(sample-structure-core sample-structure-core.cpp)
target_link_libraries(sample-structure-core ${VISP_LIBRARIES})

To acquire images from the Structure Core color camera and convert them into grey level images, a good starting is to use the following code that corresponds to the content of `sample-structure-core.cpp:

#include <visp3/gui/vpDisplayGDI.h>
#include <visp3/gui/vpDisplayX.h>
#include <visp3/sensor/vpOccipitalStructure.h>
int main()
{
ST::CaptureSessionSettings settings;
settings.source = ST::CaptureSessionSourceId::StructureCore;
settings.structureCore.visibleEnabled = true;
sc.open(settings);
#ifdef VISP_HAVE_X11
vpDisplayX d(I);
#elif defined(VISP_HAVE_GDI)
#endif
while (true) {
sc.acquire(I);
if (vpDisplay::getClick(I, false))
break;
}
return 0;
}
Display for windows using GDI (available on any windows 32 platform).
Definition: vpDisplayGDI.h:128
Use the X11 console to display images on unix-like OS. Thus to enable this class X11 should be instal...
Definition: vpDisplayX.h:128
static bool getClick(const vpImage< unsigned char > &I, bool blocking=true)
static void display(const vpImage< unsigned char > &I)
static void flush(const vpImage< unsigned char > &I)
unsigned int getHeight(vpOccipitalStructureStream stream_type)
void acquire(vpImage< unsigned char > &gray, bool undistorted=false, double *ts=nullptr)
unsigned int getWidth(vpOccipitalStructureStream stream_type)
bool open(const ST::CaptureSessionSettings &settings)

If you want to acquire color images, in the previous sample replace:

by

If you are interested in the point cloud and if ViSP is build with PCL support, you can start from the following example where we use PCL library to visualize the point cloud

#include <pcl/visualization/cloud_viewer.h>
#include <pcl/visualization/pcl_visualizer.h>
#include <visp3/sensor/vpOccipitalStructure.h>
int main()
{
ST::CaptureSessionSettings settings;
settings.source = ST::CaptureSessionSourceId::StructureCore;
settings.structureCore.visibleEnabled = true;
settings.applyExpensiveCorrection = true; // Apply a correction and clean filter to the depth before streaming.
sc.open(settings);
// Calling these 2 functions to set internal variables.
pcl::PointCloud<pcl::PointXYZRGB>::Ptr pointcloud(new pcl::PointCloud<pcl::PointXYZRGB>);
sc.acquire(nullptr, nullptr, nullptr, pointcloud);
pcl::visualization::PCLVisualizer::Ptr viewer (new pcl::visualization::PCLVisualizer ("3D Viewer"));
pcl::visualization::PointCloudColorHandlerRGBField<pcl::PointXYZRGB> rgb(pointcloud);
viewer->setBackgroundColor(0, 0, 0);
viewer->initCameraParameters();
viewer->setCameraPosition(0, 0, -0.5, 0, -1, 0);
while (true) {
sc.acquire(nullptr, nullptr, nullptr, pointcloud);
static bool update = false;
if (!update) {
viewer->addPointCloud<pcl::PointXYZRGB> (pointcloud, rgb, "sample cloud");
viewer->setPointCloudRenderingProperties (pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 1, "sample cloud");
update = true;
} else {
viewer->updatePointCloud<pcl::PointXYZRGB> (pointcloud, rgb, "sample cloud");
}
viewer->spinOnce(30);
}
return 0;
}
vpCameraParameters getCameraParameters(const vpOccipitalStructureStream stream_type, vpCameraParameters::vpCameraParametersProjType type=vpCameraParameters::perspectiveProjWithoutDistortion)

References to ST::CaptureSession and ST::CaptureSessionSettings can be retrieved with (sc.open() must be called before):

ST::CaptureSession &getCaptureSession();
ST::CaptureSessionSettings &getCaptureSessionSettings();
ST::CaptureSession & getCaptureSession()
ST::CaptureSessionSettings & getCaptureSessionSettings()
Examples
testOccipitalStructure_Core_images.cpp, testOccipitalStructure_Core_imu.cpp, testOccipitalStructure_Core_pcl.cpp, tutorial-apriltag-detector-live-rgbd-structure-core.cpp, tutorial-grabber-rgbd-D435-structurecore.cpp, tutorial-grabber-structure-core.cpp, and tutorial-mb-generic-tracker-rgbd-structure-core.cpp.

Definition at line 273 of file vpOccipitalStructure.h.

Member Enumeration Documentation

◆ vpOccipitalStructureStream

Enumerator
visible 

Visible stream.

depth 

Depth stream.

infrared 

Infrared stream.

imu 

IMU stream.

Definition at line 276 of file vpOccipitalStructure.h.

Constructor & Destructor Documentation

◆ vpOccipitalStructure()

vpOccipitalStructure::vpOccipitalStructure ( )

Default constructor.

Definition at line 58 of file vpOccipitalStructure.cpp.

◆ ~vpOccipitalStructure()

vpOccipitalStructure::~vpOccipitalStructure ( )

Default destructor that stops the streaming.

See also
stop()

Definition at line 64 of file vpOccipitalStructure.cpp.

References close().

Member Function Documentation

◆ acquire() [1/7]

void vpOccipitalStructure::acquire ( unsigned char *const  data_image,
unsigned char *const  data_depth,
std::vector< vpColVector > *const  data_pointCloud,
pcl::PointCloud< pcl::PointXYZ >::Ptr &  pointcloud,
unsigned char *const  data_infrared = nullptr,
vpColVector acceleration_data = nullptr,
vpColVector gyroscope_data = nullptr,
bool  undistorted = true,
double *  ts = nullptr 
)

Acquire data from Structure Core device.

Parameters
data_image: Color image buffer or nullptr if not wanted.
data_depth: Depth image buffer or nullptr if not wanted.
data_pointCloud: Point cloud vector pointer or nullptr if not wanted.
pointcloud: Point cloud (in PCL format and without texture information) pointer or nullptr if not wanted.
data_infrared: Infrared image buffer or nullptr if not wanted.
acceleration_data: Acceleration data or nullptr if not wanted.
gyroscope_data: Gyroscope data or nullptr if not wanted.
undistorted: Set to true if you want undistorted monochrome device image.
ts: Data timestamp or nullptr if not wanted.

Definition at line 320 of file vpOccipitalStructure.cpp.

References getPointcloud(), vpImageConvert::GreyToRGBa(), m_delegate, and vpImageConvert::RGBToRGBa().

◆ acquire() [2/7]

void vpOccipitalStructure::acquire ( unsigned char *const  data_image,
unsigned char *const  data_depth,
std::vector< vpColVector > *const  data_pointCloud,
pcl::PointCloud< pcl::PointXYZRGB >::Ptr &  pointcloud,
unsigned char *const  data_infrared = nullptr,
vpColVector acceleration_data = nullptr,
vpColVector gyroscope_data = nullptr,
bool  undistorted = true,
double *  ts = nullptr 
)

Acquire data from Structure Core device.

Parameters
data_image: Color image buffer or nullptr if not wanted.
data_depth: Depth image buffer or nullptr if not wanted.
data_pointCloud: Point cloud vector pointer or nullptr if not wanted.
pointcloud: Point cloud (in PCL format) pointer or nullptr if not wanted.
data_infrared: Infrared image buffer or nullptr if not wanted.
acceleration_data: Acceleration data or nullptr if not wanted.
gyroscope_data: Gyroscope data or nullptr if not wanted.
undistorted: Set to true if you want undistorted monochrome device image.
ts: Data timestamp or nullptr if not wanted.

Definition at line 394 of file vpOccipitalStructure.cpp.

References getColoredPointcloud(), getPointcloud(), vpImageConvert::GreyToRGBa(), m_delegate, and vpImageConvert::RGBToRGBa().

◆ acquire() [3/7]

void vpOccipitalStructure::acquire ( unsigned char *const  data_image,
unsigned char *const  data_depth,
std::vector< vpColVector > *const  data_pointCloud = nullptr,
unsigned char *const  data_infrared = nullptr,
vpColVector acceleration_data = nullptr,
vpColVector gyroscope_data = nullptr,
bool  undistorted = true,
double *  ts = nullptr 
)

Acquire data from Structure Core device.

Parameters
data_image: Visible image buffer or nullptr if not wanted.
data_depth: Depth image buffer in millimeters or nullptr if not wanted.
data_pointCloud: Point cloud vector pointer or nullptr if not wanted.
data_infrared: Infrared image buffer or nullptr if not wanted.
acceleration_data: Acceleration data or nullptr if not wanted.
gyroscope_data: Gyroscope data or nullptr if not wanted.
undistorted: Set to true if you want undistorted monochrome device image.
ts: Data timestamp or nullptr if not wanted.

Definition at line 249 of file vpOccipitalStructure.cpp.

References getPointcloud(), vpImageConvert::GreyToRGBa(), m_delegate, and vpImageConvert::RGBToRGBa().

◆ acquire() [4/7]

void vpOccipitalStructure::acquire ( vpImage< unsigned char > &  gray,
bool  undistorted = false,
double *  ts = nullptr 
)

Acquire greyscale image from Structure Core device.

Parameters
gray: Greyscale image.
undistorted: Set to true to get undistorted grayscale image.
ts: Image timestamp or nullptr if not wanted.
Examples
testOccipitalStructure_Core_images.cpp, testOccipitalStructure_Core_pcl.cpp, tutorial-apriltag-detector-live-rgbd-structure-core.cpp, tutorial-grabber-rgbd-D435-structurecore.cpp, tutorial-grabber-structure-core.cpp, and tutorial-mb-generic-tracker-rgbd-structure-core.cpp.

Definition at line 72 of file vpOccipitalStructure.cpp.

References vpImage< Type >::bitmap, and m_delegate.

◆ acquire() [5/7]

void vpOccipitalStructure::acquire ( vpImage< unsigned char > *  gray,
vpImage< vpRGBa > *  depth,
vpColVector acceleration_data = nullptr,
vpColVector gyroscope_data = nullptr,
bool  undistorted = false,
double *  ts = nullptr 
)

Acquire grayscale image, depth and IMU data from Structure Core device.

Parameters
gray: Gray image or nullptr if not wanted.
depth: Depth image or nullptr if not wanted.
acceleration_data: Acceleration data or nullptr if not wanted.
gyroscope_data: Gyroscope data or nullptr if not wanted.
undistorted: Set to true to get undistorted image.
ts: Image timestamp or nullptr if not wanted.

Definition at line 198 of file vpOccipitalStructure.cpp.

References vpImage< Type >::bitmap, depth, and m_delegate.

◆ acquire() [6/7]

void vpOccipitalStructure::acquire ( vpImage< vpRGBa > &  rgb,
bool  undistorted = false,
double *  ts = nullptr 
)

Acquire color image from Structure Core device.

Parameters
rgb: RGB image.
undistorted: Set to true to get undistorted image.
ts: Image timestamp or nullptr if not wanted.

Definition at line 96 of file vpOccipitalStructure.cpp.

References vpImage< Type >::bitmap, vpImageConvert::GreyToRGBa(), m_delegate, and vpImageConvert::RGBToRGBa().

◆ acquire() [7/7]

void vpOccipitalStructure::acquire ( vpImage< vpRGBa > *  rgb,
vpImage< vpRGBa > *  depth,
vpColVector acceleration_data = nullptr,
vpColVector gyroscope_data = nullptr,
bool  undistorted = false,
double *  ts = nullptr 
)

Acquire rgb image and IMU data from Structure Core device.

Parameters
rgb: RGB image or nullptr if not wanted.
depth: Depth image or nullptr if not wanted.
acceleration_data: Acceleration data or nullptr if not wanted.
gyroscope_data: Gyroscope data or nullptr if not wanted.
undistorted: Set to true to get undistorted image.
ts: Image timestamp or nullptr if not wanted.

Definition at line 136 of file vpOccipitalStructure.cpp.

References vpImage< Type >::bitmap, depth, vpImageConvert::GreyToRGBa(), m_delegate, and vpImageConvert::RGBToRGBa().

◆ close()

void vpOccipitalStructure::close ( )

libStructure documentation:

Unlike the start functions, this function runs synchronously and will block until the device has successfully stopped streaming. Once successful, the captureSessionEventDidOccur delegate will receive CaptureSessionEventId::Ready. If an error occurs, the captureSessionEventDidOccur delegate will receive CaptureSessionEventId::Error or the specific error case enum.

Definition at line 636 of file vpOccipitalStructure.cpp.

References m_captureSession, and m_init.

Referenced by open(), and ~vpOccipitalStructure().

◆ getCameraParameters()

Get intrinsic parameters of input stream type.

Parameters
stream_type: Type of stream (visible, depth).
proj_type: Perspective projection model type; with or without distortion.
Examples
testOccipitalStructure_Core_pcl.cpp, tutorial-apriltag-detector-live-rgbd-structure-core.cpp, and tutorial-mb-generic-tracker-rgbd-structure-core.cpp.

Definition at line 916 of file vpOccipitalStructure.cpp.

References m_delegate, m_depth_camera_parameters, m_visible_camera_parameters, vpCameraParameters::perspectiveProjWithDistortion, and vpCameraParameters::perspectiveProjWithoutDistortion.

◆ getCameraType()

ST::StructureCoreCameraType vpOccipitalStructure::getCameraType ( ) const
inline

Get camera type: Color or Monochrome.

Definition at line 321 of file vpOccipitalStructure.h.

◆ getCaptureSession()

ST::CaptureSession& vpOccipitalStructure::getCaptureSession ( )
inline

Definition at line 325 of file vpOccipitalStructure.h.

◆ getCaptureSessionSettings()

ST::CaptureSessionSettings& vpOccipitalStructure::getCaptureSessionSettings ( )
inline

Definition at line 326 of file vpOccipitalStructure.h.

◆ getColoredPointcloud()

void vpOccipitalStructure::getColoredPointcloud ( pcl::PointCloud< pcl::PointXYZRGB >::Ptr &  pointcloud)
protected

◆ getDepth()

float vpOccipitalStructure::getDepth ( int  x,
int  y 
)

Returns depth in millimeters at (x,y) if it exists, NAN otherwise.

Parameters
x: Pixel x-location.
y: Pixel y-location

Definition at line 707 of file vpOccipitalStructure.cpp.

References m_delegate.

◆ getHeight()

unsigned int vpOccipitalStructure::getHeight ( vpOccipitalStructureStream  stream_type)

Returns height of given stream image.

Parameters
stream_type: Type of stream (visible, depth, infrared).
Examples
testOccipitalStructure_Core_images.cpp, testOccipitalStructure_Core_pcl.cpp, tutorial-grabber-structure-core.cpp, and tutorial-mb-generic-tracker-rgbd-structure-core.cpp.

Definition at line 677 of file vpOccipitalStructure.cpp.

References m_delegate.

◆ getIMUAcceleration()

void vpOccipitalStructure::getIMUAcceleration ( vpColVector imu_acc,
double *  ts 
)

Get linear acceleration from IMU's accelerometer.

Parameters
imu_acc: IMU 3-dim angular velocity vector from gyro.
ts: Timestamp.
Note
Default IMU streaming rate is 400Hz.
ST::CaptureSessionSettings settings;
settings.source = ST::CaptureSessionSourceId::StructureCore;
settings.structureCore.depthEnabled = false;
settings.structureCore.accelerometerEnabled = true;
settings.structureCore.gyroscopeEnabled = true;
st.open(settings);
vpColVector imu_acc;
double timestamp;
st.getIMUAcceleration(&imu_acc, &timestamp);
Implementation of column vector and the associated operations.
Definition: vpColVector.h:163
void getIMUAcceleration(vpColVector *imu_acc, double *ts)

Definition at line 519 of file vpOccipitalStructure.cpp.

References m_delegate, and vpColVector::resize().

◆ getIMUData()

void vpOccipitalStructure::getIMUData ( vpColVector imu_vel,
vpColVector imu_acc,
double *  ts = nullptr 
)

Get IMU data (angular velocities and linear acceleration) from Structure Core device.

Parameters
imu_vel: IMU 3-dim angular velocity vector from gyro.
imu_acc: IMU 3-dim linear acceleration vector.
ts: Timestamp.
Note
Default IMU streaming rate is 400Hz.
Be aware that IMU frame's X and Z axes are opposite to X and Z axes of pose frame.
ST::CaptureSessionSettings settings;
settings.source = ST::CaptureSessionSourceId::StructureCore;
settings.structureCore.depthEnabled = false;
settings.structureCore.accelerometerEnabled = true;
settings.structureCore.gyroscopeEnabled = true;
st.open(settings);
vpColVector imu_acc, imu_vel;
double timestamp;
st.getIMUData(&imu_acc, &imu_vel, &timestamp);
void getIMUData(vpColVector *imu_vel, vpColVector *imu_acc, double *ts=nullptr)
Examples
testOccipitalStructure_Core_imu.cpp.

Definition at line 561 of file vpOccipitalStructure.cpp.

References m_delegate, and vpColVector::resize().

◆ getIMUVelocity()

void vpOccipitalStructure::getIMUVelocity ( vpColVector imu_vel,
double *  ts 
)

Get angular velocities from IMU's gyroscope.

Parameters
imu_vel: IMU 3-dim angular velocity vector from gyro.
ts: Timestamp.
Note
Default IMU streaming rate is 400Hz.
ST::CaptureSessionSettings settings;
settings.source = ST::CaptureSessionSourceId::StructureCore;
settings.structureCore.depthEnabled = false;
settings.structureCore.accelerometerEnabled = true;
settings.structureCore.gyroscopeEnabled = true;
st.open(settings);
vpColVector imu_vel;
double timestamp;
st.getIMUVelocity(&imu_vel, &timestamp);
void getIMUVelocity(vpColVector *imu_vel, double *ts)

Definition at line 479 of file vpOccipitalStructure.cpp.

References m_delegate, and vpColVector::resize().

◆ getIntrinsics()

ST::Intrinsics vpOccipitalStructure::getIntrinsics ( const vpOccipitalStructureStream  stream_type) const

Get intrinsic parameters corresponding to the stream. This function has to be called after open().

Parameters
stream_type: Stream for which the camera intrinsic parameters are returned.

Definition at line 876 of file vpOccipitalStructure.cpp.

References depth, infrared, m_delegate, and visible.

◆ getPointcloud() [1/2]

void vpOccipitalStructure::getPointcloud ( pcl::PointCloud< pcl::PointXYZ >::Ptr &  pointcloud)
protected

Definition at line 992 of file vpOccipitalStructure.cpp.

References m_delegate, m_invalidDepthValue, and m_maxZ.

◆ getPointcloud() [2/2]

void vpOccipitalStructure::getPointcloud ( std::vector< vpColVector > &  pointcloud)
protected

Definition at line 949 of file vpOccipitalStructure.cpp.

References m_delegate, m_invalidDepthValue, and m_maxZ.

Referenced by acquire().

◆ getSerialNumber()

std::string vpOccipitalStructure::getSerialNumber ( ) const
inline

Definition at line 324 of file vpOccipitalStructure.h.

◆ getTransform()

vpHomogeneousMatrix vpOccipitalStructure::getTransform ( const vpOccipitalStructureStream  from,
const vpOccipitalStructureStream  to 
)

Get the extrinsic transformation from one stream to another. This function has to be called after open().

Parameters
from,to: Streams for which the camera extrinsic parameters are returned.
Examples
tutorial-mb-generic-tracker-rgbd-structure-core.cpp.

Definition at line 748 of file vpOccipitalStructure.cpp.

References depth, imu, infrared, m_captureSession, m_delegate, and visible.

◆ getUSBVersion()

ST::CaptureSessionUSBVersion vpOccipitalStructure::getUSBVersion ( ) const
inline

Definition at line 323 of file vpOccipitalStructure.h.

◆ getWidth()

unsigned int vpOccipitalStructure::getWidth ( vpOccipitalStructureStream  stream_type)

Returns width of given stream image.

Parameters
stream_type: Type of stream (visible, depth, infrared).
Examples
testOccipitalStructure_Core_images.cpp, testOccipitalStructure_Core_pcl.cpp, tutorial-grabber-structure-core.cpp, and tutorial-mb-generic-tracker-rgbd-structure-core.cpp.

Definition at line 648 of file vpOccipitalStructure.cpp.

References m_delegate.

◆ open()

bool vpOccipitalStructure::open ( const ST::CaptureSessionSettings &  settings)

◆ saveDepthImageAsPointCloudMesh()

void vpOccipitalStructure::saveDepthImageAsPointCloudMesh ( std::string &  filename)

Converts the depth frame into a 3D point cloud using intrinsic calibration then writes out the result as PLY mesh at the provided path.

Parameters
filename: PLY file name.

Definition at line 906 of file vpOccipitalStructure.cpp.

References m_delegate.

◆ unprojectPoint()

vpPoint vpOccipitalStructure::unprojectPoint ( int  row,
int  col 
)

Returns 3D coordinates of point whose projection is at (row, col).

Parameters
row: Pixel row.
col: Pixel column.

Definition at line 727 of file vpOccipitalStructure.cpp.

References m_delegate.

Member Data Documentation

◆ m_captureSession

ST::CaptureSession vpOccipitalStructure::m_captureSession
protected

Definition at line 351 of file vpOccipitalStructure.h.

Referenced by close(), getTransform(), and open().

◆ m_captureSessionSettings

ST::CaptureSessionSettings vpOccipitalStructure::m_captureSessionSettings
protected

Definition at line 352 of file vpOccipitalStructure.h.

Referenced by open().

◆ m_delegate

◆ m_depth_camera_parameters

vpCameraParameters vpOccipitalStructure::m_depth_camera_parameters
protected

Definition at line 354 of file vpOccipitalStructure.h.

Referenced by getCameraParameters().

◆ m_init

bool vpOccipitalStructure::m_init
protected

Definition at line 347 of file vpOccipitalStructure.h.

Referenced by close(), and open().

◆ m_invalidDepthValue

float vpOccipitalStructure::m_invalidDepthValue
protected

Definition at line 348 of file vpOccipitalStructure.h.

Referenced by getColoredPointcloud(), and getPointcloud().

◆ m_maxZ

float vpOccipitalStructure::m_maxZ
protected

Definition at line 349 of file vpOccipitalStructure.h.

Referenced by getColoredPointcloud(), and getPointcloud().

◆ m_visible_camera_parameters

vpCameraParameters vpOccipitalStructure::m_visible_camera_parameters
protected

Definition at line 354 of file vpOccipitalStructure.h.

Referenced by getCameraParameters(), and getColoredPointcloud().