Main MRPT website > C++ reference for MRPT 1.9.9
List of all members | Public Types | Public Member Functions | Static Public Member Functions | Protected Member Functions | Protected Attributes | Static Protected Attributes
mrpt::hwdrivers::COpenNI2Sensor Class Referenceabstract

Detailed Description

A class for grabing "range images", intensity images (either RGB or IR) and other information from an OpenNI2 sensor.

This class permits to access several sensors simultaneously. The same options (resolution, fps, etc.) are used for every sensor.

Configuration and usage:


Data is returned as observations of type mrpt::obs::CObservation3DRangeScan. See those classes for documentation on their fields.

As with any other CGenericSensor class, the normal sequence of methods to be called is:

Calibration parameters


In this class we employ the OpenNI2 method to return depth images refered to the RGB camera. Otherwise we could specify an accurate transformation of depth images to 3D points, you'll have to calibrate your RGBD sensor for that, and supply the following threee pieces of information (default calibration data will be used otherwise, but they'll be not optimal for all sensors!):

See http://www.mrpt.org/Kinect_calibration for a procedure to calibrate RGBD sensors with an interactive GUI program.

Coordinates convention


The origin of coordinates is the focal point of the depth camera, with the axes oriented as in the diagram shown in mrpt::obs::CObservation3DRangeScan. Notice in that picture that the RGB camera is assumed to have axes as usual in computer vision, which differ from those for the depth camera.

The X,Y,Z axes used to report the data from accelerometers coincide with those of the depth camera (e.g. the camera standing on a table would have an ACC_Z=-9.8m/s2).

Notice however that, for consistency with stereo cameras, when loading the calibration parameters from a configuration file, the left-to-right pose increment is expected as if both RGB & IR cameras had their +Z axes pointing forward, +X to the right, +Y downwards (just like it's the standard in stereo cameras and in computer vision literature). In other words: the pose stored in this class uses a different axes convention for the depth camera than in a stereo camera, so when a pose L2R is loaded from a calibration file it's actually converted like:

L2R(this class convention) = CPose3D(0,0,0,-90deg,0deg,-90deg) (+) L2R(in the config file)

Some general comments


Converting to 3D point cloud


You can convert the 3D observation into a 3D point cloud with this piece of code:

pntsMap.colorScheme.scheme = CColouredPointsMap::cmFromIntensityImage;
pntsMap.loadFromRangeScan(obs3D);

Then the point cloud mrpt::maps::CColouredPointsMap can be converted into an OpenGL object for rendering with mrpt::maps::CMetricMap::getAs3DObject() or alternatively with:

*mrpt::make_aligned_shared<mrpt::opengl::CPointCloudColoured>();
gl_points->loadFromPointsMap(&pntsMap);

Platform-specific comments


For more details, refer to libfreenect documentation:

Format of parameters for loading from a .ini file


PARAMETERS IN THE ".INI"-LIKE CONFIGURATION STRINGS:
-------------------------------------------------------
[supplied_section_name]
sensorLabel = OPENNI2 // A text description
preview_window = false // Show a window with a preview of the
*grabbed data in real-time
device_number = 0 // Device index to open (0:first Kinect,
1:second Kinect,...)
grab_image = true // Grab the RGB image channel?
*(Default=true)
grab_depth = true // Grab the depth channel? (Default=true)
grab_3D_points = true // Grab the 3D point cloud? (Default=true)
*If disabled, points can be generated later on.
video_channel = VIDEO_CHANNEL_RGB // Optional. Can be:
*VIDEO_CHANNEL_RGB (default) or VIDEO_CHANNEL_IR
pose_x=0 // Camera position in the robot (meters)
pose_y=0
pose_z=0
pose_yaw=0 // Angles in degrees
pose_pitch=0
pose_roll=0
// Kinect sensor calibration:
// See http://www.mrpt.org/Kinect_and_MRPT
// Left/Depth camera
[supplied_section_name_LEFT]
rawlog-grabber-ignore = true // Instructs rawlog-grabber to ignore this
*section (it is not a separate device!)
resolution = [640 488]
cx = 314.649173
cy = 240.160459
fx = 572.882768
fy = 542.739980
dist = [-4.747169e-03 -4.357976e-03 0.000000e+00 0.000000e+00
0.000000e+00] // The order is: [K1 K2 T1 T2 K3]
// Right/RGB camera
[supplied_section_name_RIGHT]
rawlog-grabber-ignore = true // Instructs rawlog-grabber to ignore this
*section (it is not a separate device!)
resolution = [640 480]
cx = 322.515987
cy = 259.055966
fx = 521.179233
fy = 493.033034
dist = [5.858325e-02 3.856792e-02 0.000000e+00 0.000000e+00
0.000000e+00] // The order is: [K1 K2 T1 T2 K3]
// Relative pose of the right camera wrt to the left camera:
// This assumes that both camera frames are such that +Z points
// forwards, and +X and +Y to the right and downwards.
// For the actual coordinates employed in 3D observations, see figure in
*mrpt::obs::CObservation3DRangeScan
[supplied_section_name_LEFT2RIGHT_POSE]
rawlog-grabber-ignore = true // Instructs rawlog-grabber to ignore this
*section (it is not a separate device!)
pose_quaternion = [0.025575 -0.000609 -0.001462 0.999987 0.002038
0.004335 -0.001693]

More references to read:IMPEXP mrpt

Definition at line 219 of file COpenNI2Sensor.h.

#include <mrpt/hwdrivers/COpenNI2Sensor.h>

Inheritance diagram for mrpt::hwdrivers::COpenNI2Sensor:
Inheritance graph

Public Types

enum  TSensorState { ssInitializing = 0, ssWorking, ssError }
 The current state of the sensor. More...
 
using Ptr = std::shared_ptr< CGenericSensor >
 
typedef std::multimap< mrpt::system::TTimeStamp, mrpt::utils::CSerializable::PtrTListObservations
 
typedef std::pair< mrpt::system::TTimeStamp, mrpt::utils::CSerializable::PtrTListObsPair
 

Public Member Functions

 COpenNI2Sensor ()
 Default ctor. More...
 
 ~COpenNI2Sensor ()
 Default ctor. More...
 
void setSerialToOpen (const unsigned serial)
 Set the serial number of the device to open. More...
 
void setSensorIDToOpen (const unsigned sensor_id)
 Set the sensor_id of the device to open. More...
 
virtual void initialize ()
 Initializes the 3D camera - should be invoked after calling loadConfig() or setting the different parameters with the set*() methods. More...
 
virtual void doProcess ()
 To be called at a high rate (>XX Hz), this method populates the internal buffer of received observations. More...
 
void getNextObservation (mrpt::obs::CObservation3DRangeScan &out_obs, bool &there_is_obs, bool &hardware_error)
 The main data retrieving function, to be called after calling loadConfig() and initialize(). More...
 
virtual void setPathForExternalImages (const std::string &directory)
 Set the path where to save off-rawlog image files (this class DOES take into account this path). More...
 
virtual const mrpt::hwdrivers::TSensorClassIdGetRuntimeClass () const =0
 
TSensorState getState () const
 The current state of the sensor. More...
 
double getProcessRate () const
 
std::string getSensorLabel () const
 
void setSensorLabel (const std::string &sensorLabel)
 
void enableVerbose (bool enabled=true)
 Enable or disable extra debug info dumped to std::cout during sensor operation. More...
 
bool isVerboseEnabled () const
 
void loadConfig (const mrpt::utils::CConfigFileBase &configSource, const std::string &section)
 Loads the generic settings common to any sensor (See CGenericSensor), then call to "loadConfig_sensorSpecific". More...
 
void getObservations (TListObservations &lstObjects)
 Returns a list of enqueued objects, emptying it (thread-safe). More...
 
void setExternalImageFormat (const std::string &ext)
 Set the extension ("jpg","gif","png",...) that determines the format of images saved externally The default is "jpg". More...
 
void setExternalImageJPEGQuality (const unsigned int quality)
 The quality of JPEG compression, when external images is enabled and the format is "jpg". More...
 
unsigned int getExternalImageJPEGQuality () const
 
void getNextFrameRGB (mrpt::utils::CImage &rgb_img, uint64_t &timestamp, bool &there_is_obs, bool &hardware_error, unsigned sensor_id=0)
 The main data retrieving function, to be called after calling loadConfig() and initialize(). More...
 
void getNextFrameD (mrpt::math::CMatrix &depth_img, uint64_t &timestamp, bool &there_is_obs, bool &hardware_error, unsigned sensor_id=0)
 The main data retrieving function, to be called after calling loadConfig() and initialize(). More...
 
void getNextFrameRGBD (mrpt::obs::CObservation3DRangeScan &out_obs, bool &there_is_obs, bool &hardware_error, unsigned sensor_id=0)
 The main data retrieving function, to be called after calling loadConfig() and initialize(). More...
 
void setVerbose (bool verbose)
 
bool isVerbose () const
 
bool getColorSensorParam (mrpt::utils::TCamera &param, unsigned sensor_id=0) const
 
bool getDepthSensorParam (mrpt::utils::TCamera &param, unsigned sensor_id=0) const
 
Sensor parameters (alternative to \a loadConfig ) and manual

control

double getMaxRange () const
 Get the maximum range (meters) that can be read in the observation field "rangeImage". More...
 
size_t getRowCount () const
 Get the row count in the camera images, loaded automatically upon camera open(). More...
 
size_t getColCount () const
 Get the col count in the camera images, loaded automatically upon camera open(). More...
 
const mrpt::utils::TCameragetCameraParamsIntensity () const
 Get a const reference to the depth camera calibration parameters. More...
 
void setCameraParamsIntensity (const mrpt::utils::TCamera &p)
 
const mrpt::utils::TCameragetCameraParamsDepth () const
 Get a const reference to the depth camera calibration parameters. More...
 
void setCameraParamsDepth (const mrpt::utils::TCamera &p)
 
void setRelativePoseIntensityWrtDepth (const mrpt::poses::CPose3D &p)
 Set the pose of the intensity camera wrt the depth camera. More...
 
const mrpt::poses::CPose3DgetRelativePoseIntensityWrtDepth () const
 
void enableGrabRGB (bool enable=true)
 Enable/disable the grabbing of the RGB channel. More...
 
bool isGrabRGBEnabled () const
 
void enableGrabDepth (bool enable=true)
 Enable/disable the grabbing of the depth channel. More...
 
bool isGrabDepthEnabled () const
 
void enableGrab3DPoints (bool enable=true)
 Enable/disable the grabbing of the 3D point clouds. More...
 
bool isGrab3DPointsEnabled () const
 
Open/Close device methods
void open (unsigned sensor_id=0)
 Try to open the camera (all the parameters [resolution,fps,...] must be set before calling this) - users may also call initialize(), which in turn calls this method. More...
 
unsigned int openDevicesBySerialNum (const std::set< unsigned > &vSerialRequired)
 Open a set of RGBD devices specified by their serial number. More...
 
unsigned int openDeviceBySerial (const unsigned int SerialRequired)
 Open a RGBD device specified by its serial number. More...
 
bool getDeviceIDFromSerialNum (const unsigned int SerialRequired, int &sensor_id) const
 Get the ID of the device corresponding to 'SerialRequired'. More...
 
bool start ()
 Open all sensor streams (normally called automatically at constructor, no need to call it manually). More...
 
void kill ()
 Kill the OpenNI2 driver. More...
 
bool isOpen (const unsigned sensor_id) const
 Whether there is a working connection to the sensor. More...
 
void close (unsigned sensor_id=0)
 Close the connection to the sensor (no need to call it manually unless desired for some reason, since it's called at destructor. More...
 
int getNumDevices () const
 The number of available devices at initialization. More...
 
int getConnectedDevices ()
 Get a list of the connected OpenNI2 sensors. More...
 

Static Public Member Functions

static void registerClass (const TSensorClassId *pNewClass)
 Register a class into the internal list of "CGenericSensor" descendents. More...
 
static CGenericSensorcreateSensor (const std::string &className)
 Creates a sensor by a name of the class. More...
 
static CGenericSensor::Ptr createSensorPtr (const std::string &className)
 Just like createSensor, but returning a smart pointer to the newly created sensor object. More...
 

Protected Member Functions

virtual void loadConfig_sensorSpecific (const mrpt::utils::CConfigFileBase &configSource, const std::string &section)
 Loads specific configuration for the device from a given source of configuration parameters, for example, an ".ini" file, loading from the section "[iniSection]" (see utils::CConfigFileBase and derived classes) More...
 
void appendObservations (const std::vector< mrpt::utils::CSerializable::Ptr > &obj)
 This method must be called by derived classes to enqueue a new observation in the list to be returned by getObservations. More...
 
void appendObservation (const mrpt::utils::CSerializable::Ptr &obj)
 Like appendObservations() but for just one observation. More...
 
void showLog (const std::string &message) const
 

Protected Attributes

mrpt::poses::CPose3D m_sensorPoseOnRobot
 
bool m_preview_window
 Show preview window while grabbing. More...
 
size_t m_preview_window_decimation
 If preview is enabled, only show 1 out of N images. More...
 
size_t m_preview_decim_counter_range
 
size_t m_preview_decim_counter_rgb
 
mrpt::gui::CDisplayWindow::Ptr m_win_range
 
mrpt::gui::CDisplayWindow::Ptr m_win_int
 
mrpt::utils::TCamera m_cameraParamsRGB
 Params for the RGB camera. More...
 
mrpt::utils::TCamera m_cameraParamsDepth
 Params for the Depth camera. More...
 
mrpt::poses::CPose3D m_relativePoseIntensityWRTDepth
 See mrpt::obs::CObservation3DRangeScan for a diagram of this pose. More...
 
double m_maxRange
 Sensor max range (meters) More...
 
int m_user_device_number
 Number of device to open (0:first,...) More...
 
int m_serial_number
 Serial number of device to open. More...
 
size_t m_grab_decimation_counter
 Used when "m_grab_decimation" is enabled. More...
 
TSensorState m_state
 
bool m_verbose
 
std::string m_path_for_external_images
 The path where to save off-rawlog images: empty means save images embedded in the rawlog. More...
 
std::string m_external_images_format
 The extension ("jpg","gif","png",...) that determines the format of images saved externally. More...
 
unsigned int m_external_images_jpeg_quality
 For JPEG images, the quality (default=95%). More...
 
std::vector< int > vSerialNums
 A vector with the serial numbers of the available devices. More...
 
int m_width
 The same options (width, height and fps) are set for all the sensors. More...
 
int m_height
 
float m_fps
 
int m_rgb_format
 
int m_depth_format
 
bool m_verbose
 
bool m_grab_image
 The data that the RGBD sensors can return. More...
 
bool m_grab_depth
 
bool m_grab_3D_points
 
Common settings to any sensor, loaded in "loadConfig"
double m_process_rate
 See CGenericSensor. More...
 
size_t m_max_queue_len
 See CGenericSensor. More...
 
size_t m_grab_decimation
 If set to N>=2, only 1 out of N observations will be saved to m_objList. More...
 
std::string m_sensorLabel
 See CGenericSensor. More...
 

Static Protected Attributes

static std::vector< std::shared_ptr< CDevice > > vDevices
 
static int numInstances = 0
 

Member Typedef Documentation

◆ Ptr

using mrpt::hwdrivers::CGenericSensor::Ptr = std::shared_ptr<CGenericSensor>
inherited

Definition at line 73 of file CGenericSensor.h.

◆ TListObservations

Definition at line 78 of file CGenericSensor.h.

◆ TListObsPair

Definition at line 80 of file CGenericSensor.h.

Member Enumeration Documentation

◆ TSensorState

The current state of the sensor.

See also
CGenericSensor::getState
Enumerator
ssInitializing 
ssWorking 
ssError 

Definition at line 85 of file CGenericSensor.h.

Constructor & Destructor Documentation

◆ COpenNI2Sensor()

COpenNI2Sensor::COpenNI2Sensor ( )

Default ctor.

Definition at line 38 of file COpenNI2Sensor.cpp.

◆ ~COpenNI2Sensor()

COpenNI2Sensor::~COpenNI2Sensor ( )

Default ctor.

Definition at line 80 of file COpenNI2Sensor.cpp.

Member Function Documentation

◆ appendObservation()

void mrpt::hwdrivers::CGenericSensor::appendObservation ( const mrpt::utils::CSerializable::Ptr obj)
inlineprotectedinherited

◆ appendObservations()

void CGenericSensor::appendObservations ( const std::vector< mrpt::utils::CSerializable::Ptr > &  obj)
protectedinherited

This method must be called by derived classes to enqueue a new observation in the list to be returned by getObservations.

Passed objects must be created in dynamic memory and a smart pointer passed. Example of creation:

mrpt::obs::CObservationGPS::Ptr o = CObservationGPS::Ptr( new
CObservationGPS() );
o-> .... // Set data

If several observations are passed at once in the vector, they'll be considered as a block regarding the grabbing decimation factor.

Definition at line 53 of file CGenericSensor.cpp.

References CLASS_ID, mrpt::hwdrivers::CGenericSensor::m_csObjList, mrpt::hwdrivers::CGenericSensor::m_grab_decimation, mrpt::hwdrivers::CGenericSensor::m_grab_decimation_counter, mrpt::hwdrivers::CGenericSensor::m_objList, and THROW_EXCEPTION.

Referenced by mrpt::hwdrivers::CGenericSensor::appendObservation(), mrpt::hwdrivers::CNationalInstrumentsDAQ::doProcess(), and mrpt::hwdrivers::CKinect::doProcess().

Here is the caller graph for this function:

◆ close()

void COpenNI2Generic::close ( unsigned  sensor_id = 0)
inherited

Close the connection to the sensor (no need to call it manually unless desired for some reason, since it's called at destructor.

Definition at line 389 of file COpenNI2Generic.cpp.

References mrpt::hwdrivers::COpenNI2Generic::getNumDevices(), MRPT_UNUSED_PARAM, THROW_EXCEPTION, and mrpt::hwdrivers::COpenNI2Generic::vDevices.

Here is the call graph for this function:

◆ createSensor()

CGenericSensor * CGenericSensor::createSensor ( const std::string className)
staticinherited

Creates a sensor by a name of the class.

Typically the user may want to create a smart pointer around the returned pointer, whis is made with:

Returns
A pointer to a new class, or nullptr if class name is unknown.

Definition at line 103 of file CGenericSensor.cpp.

References mrpt::hwdrivers::CGenericSensor::get_registered_sensor_classes().

Referenced by mrpt::hwdrivers::CGenericSensor::createSensorPtr().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ createSensorPtr()

static CGenericSensor::Ptr mrpt::hwdrivers::CGenericSensor::createSensorPtr ( const std::string className)
inlinestaticinherited

Just like createSensor, but returning a smart pointer to the newly created sensor object.

Definition at line 220 of file CGenericSensor.h.

References mrpt::hwdrivers::CGenericSensor::createSensor().

Here is the call graph for this function:

◆ doProcess()

void COpenNI2Sensor::doProcess ( )
virtual

To be called at a high rate (>XX Hz), this method populates the internal buffer of received observations.

This method will be invoked at a minimum rate of "process_rate" (Hz)

This method is mainly intended for usage within rawlog-grabber or similar programs. For an alternative, see getNextObservation()

Exceptions
Thismethod must throw an exception with a descriptive message if some critical error is found.
See also
getNextObservation
Exceptions
Thismethod must throw an exception with a descriptive message if some critical error is found.

Implements mrpt::hwdrivers::CGenericSensor.

Definition at line 156 of file COpenNI2Sensor.cpp.

References THROW_EXCEPTION.

◆ enableGrab3DPoints()

void mrpt::hwdrivers::COpenNI2Sensor::enableGrab3DPoints ( bool  enable = true)
inline

Enable/disable the grabbing of the 3D point clouds.

Definition at line 341 of file COpenNI2Sensor.h.

References mrpt::hwdrivers::COpenNI2Generic::m_grab_3D_points.

◆ enableGrabDepth()

void mrpt::hwdrivers::COpenNI2Sensor::enableGrabDepth ( bool  enable = true)
inline

Enable/disable the grabbing of the depth channel.

Definition at line 338 of file COpenNI2Sensor.h.

References mrpt::hwdrivers::COpenNI2Generic::m_grab_depth.

◆ enableGrabRGB()

void mrpt::hwdrivers::COpenNI2Sensor::enableGrabRGB ( bool  enable = true)
inline

Enable/disable the grabbing of the RGB channel.

Definition at line 335 of file COpenNI2Sensor.h.

References mrpt::hwdrivers::COpenNI2Generic::m_grab_image.

◆ enableVerbose()

void mrpt::hwdrivers::CGenericSensor::enableVerbose ( bool  enabled = true)
inlineinherited

Enable or disable extra debug info dumped to std::cout during sensor operation.

Default: disabled unless the environment variable "MRPT_HWDRIVERS_VERBOSE" is set to "1" during object creation.

Definition at line 106 of file CGenericSensor.h.

References mrpt::hwdrivers::CGenericSensor::m_verbose.

◆ getCameraParamsDepth()

const mrpt::utils::TCamera& mrpt::hwdrivers::COpenNI2Sensor::getCameraParamsDepth ( ) const
inline

Get a const reference to the depth camera calibration parameters.

Definition at line 314 of file COpenNI2Sensor.h.

References m_cameraParamsDepth.

◆ getCameraParamsIntensity()

const mrpt::utils::TCamera& mrpt::hwdrivers::COpenNI2Sensor::getCameraParamsIntensity ( ) const
inline

Get a const reference to the depth camera calibration parameters.

Definition at line 304 of file COpenNI2Sensor.h.

References m_cameraParamsRGB.

◆ getColCount()

size_t mrpt::hwdrivers::COpenNI2Sensor::getColCount ( ) const
inline

Get the col count in the camera images, loaded automatically upon camera open().

Definition at line 302 of file COpenNI2Sensor.h.

References m_cameraParamsRGB, and mrpt::utils::TCamera::ncols.

◆ getColorSensorParam()

bool COpenNI2Generic::getColorSensorParam ( mrpt::utils::TCamera param,
unsigned  sensor_id = 0 
) const
inherited

◆ getConnectedDevices()

int COpenNI2Generic::getConnectedDevices ( )
inherited

Get a list of the connected OpenNI2 sensors.

This method can or cannot be implemented in the derived class, depending on the need for it.

Exceptions
Thismethod must throw an exception with a descriptive message if some critical error is found.

Definition at line 164 of file COpenNI2Generic.cpp.

References mrpt::mrpt::format(), mrpt::hwdrivers::COpenNI2Generic::getNumDevices(), mrpt::hwdrivers::COpenNI2Generic::m_depth_format, mrpt::hwdrivers::COpenNI2Generic::m_rgb_format, mrpt::hwdrivers::COpenNI2Generic::m_verbose, mrpt::hwdrivers::COpenNI2Generic::showLog(), THROW_EXCEPTION, and mrpt::hwdrivers::COpenNI2Generic::vDevices.

Here is the call graph for this function:

◆ getDepthSensorParam()

bool COpenNI2Generic::getDepthSensorParam ( mrpt::utils::TCamera param,
unsigned  sensor_id = 0 
) const
inherited

◆ getDeviceIDFromSerialNum()

bool COpenNI2Generic::getDeviceIDFromSerialNum ( const unsigned int  SerialRequired,
int &  sensor_id 
) const
inherited

Get the ID of the device corresponding to 'SerialRequired'.

Definition at line 364 of file COpenNI2Generic.cpp.

References MRPT_UNUSED_PARAM, THROW_EXCEPTION, and mrpt::hwdrivers::COpenNI2Generic::vDevices.

◆ getExternalImageJPEGQuality()

unsigned int mrpt::hwdrivers::CGenericSensor::getExternalImageJPEGQuality ( ) const
inlineinherited

◆ getMaxRange()

double mrpt::hwdrivers::COpenNI2Sensor::getMaxRange ( ) const
inline

Get the maximum range (meters) that can be read in the observation field "rangeImage".

Definition at line 296 of file COpenNI2Sensor.h.

References m_maxRange.

◆ getNextFrameD()

void COpenNI2Generic::getNextFrameD ( mrpt::math::CMatrix depth_img,
uint64_t timestamp,
bool &  there_is_obs,
bool &  hardware_error,
unsigned  sensor_id = 0 
)
inherited

The main data retrieving function, to be called after calling loadConfig() and initialize().

Parameters
depth_imgThe output retrieved depth image (only if there_is_obs=true).
timestampThe timestamp of the capture (only if there_is_obs=true).
there_is_obsIf set to false, there was no new observation.
hardware_errorTrue on hardware/comms error.
sensor_idThe index of the sensor accessed.

Definition at line 460 of file COpenNI2Generic.cpp.

References mrpt::mrpt::format(), mrpt::hwdrivers::COpenNI2Generic::getNumDevices(), MRPT_UNUSED_PARAM, mrpt::hwdrivers::COpenNI2Generic::showLog(), THROW_EXCEPTION, and mrpt::hwdrivers::COpenNI2Generic::vDevices.

Here is the call graph for this function:

◆ getNextFrameRGB()

void COpenNI2Generic::getNextFrameRGB ( mrpt::utils::CImage rgb_img,
uint64_t timestamp,
bool &  there_is_obs,
bool &  hardware_error,
unsigned  sensor_id = 0 
)
inherited

The main data retrieving function, to be called after calling loadConfig() and initialize().

Parameters
out_imgThe output retrieved RGB image (only if there_is_obs=true).
timestampThe timestamp of the capture (only if there_is_obs=true).
there_is_obsIf set to false, there was no new observation.
hardware_errorTrue on hardware/comms error.
sensor_idThe index of the sensor accessed.
out_obsThe output retrieved observation (only if there_is_obs=true).
timestampThe timestamp of the capture (only if there_is_obs=true).
there_is_obsIf set to false, there was no new observation.
hardware_errorTrue on hardware/comms error.
sensor_idThe index of the sensor accessed.

Definition at line 418 of file COpenNI2Generic.cpp.

References mrpt::mrpt::format(), mrpt::hwdrivers::COpenNI2Generic::getNumDevices(), MRPT_UNUSED_PARAM, mrpt::hwdrivers::COpenNI2Generic::showLog(), THROW_EXCEPTION, and mrpt::hwdrivers::COpenNI2Generic::vDevices.

Here is the call graph for this function:

◆ getNextFrameRGBD()

void COpenNI2Generic::getNextFrameRGBD ( mrpt::obs::CObservation3DRangeScan out_obs,
bool &  there_is_obs,
bool &  hardware_error,
unsigned  sensor_id = 0 
)
inherited

The main data retrieving function, to be called after calling loadConfig() and initialize().

Parameters
out_obsThe output retrieved observation (only if there_is_obs=true).
there_is_obsIf set to false, there was no new observation.
hardware_errorTrue on hardware/comms error.
sensor_idThe index of the sensor accessed.
See also
doProcess
Parameters
out_obsThe output retrieved observation (only if there_is_obs=true).
there_is_obsIf set to false, there was no new observation.
hardware_errorTrue on hardware/comms error.
sensor_idThe index of the sensor accessed.

Definition at line 500 of file COpenNI2Generic.cpp.

References mrpt::mrpt::format(), mrpt::hwdrivers::COpenNI2Generic::getNumDevices(), MRPT_UNUSED_PARAM, mrpt::hwdrivers::COpenNI2Generic::showLog(), THROW_EXCEPTION, and mrpt::hwdrivers::COpenNI2Generic::vDevices.

Here is the call graph for this function:

◆ getNextObservation()

void COpenNI2Sensor::getNextObservation ( mrpt::obs::CObservation3DRangeScan out_obs,
bool &  there_is_obs,
bool &  hardware_error 
)

◆ getNumDevices()

int COpenNI2Generic::getNumDevices ( ) const
inherited

◆ getObservations()

void CGenericSensor::getObservations ( TListObservations lstObjects)
inherited

Returns a list of enqueued objects, emptying it (thread-safe).

The objects must be freed by the invoker.

Definition at line 91 of file CGenericSensor.cpp.

References mrpt::hwdrivers::CGenericSensor::m_csObjList, and mrpt::hwdrivers::CGenericSensor::m_objList.

◆ getProcessRate()

double mrpt::hwdrivers::CGenericSensor::getProcessRate ( ) const
inlineinherited

Definition at line 94 of file CGenericSensor.h.

References mrpt::hwdrivers::CGenericSensor::m_process_rate.

◆ getRelativePoseIntensityWrtDepth()

const mrpt::poses::CPose3D& mrpt::hwdrivers::COpenNI2Sensor::getRelativePoseIntensityWrtDepth ( ) const
inline

Definition at line 329 of file COpenNI2Sensor.h.

References m_relativePoseIntensityWRTDepth.

◆ getRowCount()

size_t mrpt::hwdrivers::COpenNI2Sensor::getRowCount ( ) const
inline

Get the row count in the camera images, loaded automatically upon camera open().

Definition at line 299 of file COpenNI2Sensor.h.

References m_cameraParamsRGB, and mrpt::utils::TCamera::nrows.

◆ GetRuntimeClass()

virtual const mrpt::hwdrivers::TSensorClassId* mrpt::hwdrivers::CGenericSensor::GetRuntimeClass ( ) const
pure virtualinherited

◆ getSensorLabel()

std::string mrpt::hwdrivers::CGenericSensor::getSensorLabel ( ) const
inlineinherited

Definition at line 95 of file CGenericSensor.h.

References mrpt::hwdrivers::CGenericSensor::m_sensorLabel.

◆ getState()

TSensorState mrpt::hwdrivers::CGenericSensor::getState ( ) const
inlineinherited

The current state of the sensor.

Definition at line 93 of file CGenericSensor.h.

References mrpt::hwdrivers::CGenericSensor::m_state.

◆ initialize()

void COpenNI2Sensor::initialize ( void  )
virtual

Initializes the 3D camera - should be invoked after calling loadConfig() or setting the different parameters with the set*() methods.

This method can or cannot be implemented in the derived class, depending on the need for it.

Exceptions
Thismethod must throw an exception with a descriptive message if some critical error is found.

Reimplemented from mrpt::hwdrivers::CGenericSensor.

Definition at line 92 of file COpenNI2Sensor.cpp.

References mrpt::mrpt::format(), isValidParameter(), and THROW_EXCEPTION.

Here is the call graph for this function:

◆ isGrab3DPointsEnabled()

bool mrpt::hwdrivers::COpenNI2Sensor::isGrab3DPointsEnabled ( ) const
inline

◆ isGrabDepthEnabled()

bool mrpt::hwdrivers::COpenNI2Sensor::isGrabDepthEnabled ( ) const
inline

Definition at line 339 of file COpenNI2Sensor.h.

References mrpt::hwdrivers::COpenNI2Generic::m_grab_depth.

◆ isGrabRGBEnabled()

bool mrpt::hwdrivers::COpenNI2Sensor::isGrabRGBEnabled ( ) const
inline

Definition at line 336 of file COpenNI2Sensor.h.

References mrpt::hwdrivers::COpenNI2Generic::m_grab_image.

◆ isOpen()

bool COpenNI2Generic::isOpen ( const unsigned  sensor_id) const
inherited

◆ isVerbose()

bool COpenNI2Generic::isVerbose ( ) const
inherited

Definition at line 150 of file COpenNI2Generic.cpp.

References mrpt::hwdrivers::COpenNI2Generic::m_verbose.

Referenced by mrpt::hwdrivers::COpenNI2Generic::showLog().

Here is the caller graph for this function:

◆ isVerboseEnabled()

bool mrpt::hwdrivers::CGenericSensor::isVerboseEnabled ( ) const
inlineinherited

Definition at line 107 of file CGenericSensor.h.

References mrpt::hwdrivers::CGenericSensor::m_verbose.

◆ kill()

void COpenNI2Generic::kill ( )
inherited

Kill the OpenNI2 driver.

See also
start()

Definition at line 233 of file COpenNI2Generic.cpp.

References THROW_EXCEPTION, and mrpt::hwdrivers::COpenNI2Generic::vDevices.

Referenced by mrpt::hwdrivers::COpenNI2Generic::~COpenNI2Generic().

Here is the caller graph for this function:

◆ loadConfig()

void CGenericSensor::loadConfig ( const mrpt::utils::CConfigFileBase cfg,
const std::string sect 
)
inherited

Loads the generic settings common to any sensor (See CGenericSensor), then call to "loadConfig_sensorSpecific".

Exceptions
Thismethod throws an exception with a descriptive message if some critical parameter is missing or has an invalid value.

Definition at line 132 of file CGenericSensor.cpp.

References mrpt::hwdrivers::CGenericSensor::loadConfig_sensorSpecific(), mrpt::hwdrivers::CGenericSensor::m_grab_decimation, mrpt::hwdrivers::CGenericSensor::m_grab_decimation_counter, mrpt::hwdrivers::CGenericSensor::m_max_queue_len, mrpt::hwdrivers::CGenericSensor::m_process_rate, mrpt::hwdrivers::CGenericSensor::m_sensorLabel, MRPT_END, MRPT_START, mrpt::utils::CConfigFileBase::read_double(), mrpt::utils::CConfigFileBase::read_int(), and mrpt::utils::CConfigFileBase::read_string().

Here is the call graph for this function:

◆ loadConfig_sensorSpecific()

void COpenNI2Sensor::loadConfig_sensorSpecific ( const mrpt::utils::CConfigFileBase configSource,
const std::string iniSection 
)
protectedvirtual

Loads specific configuration for the device from a given source of configuration parameters, for example, an ".ini" file, loading from the section "[iniSection]" (see utils::CConfigFileBase and derived classes)

Exceptions
Thismethod must throw an exception with a descriptive message if some critical parameter is missing or has an invalid value.

Implements mrpt::hwdrivers::CGenericSensor.

Definition at line 196 of file COpenNI2Sensor.cpp.

References DEG2RAD, mrpt::utils::TStereoCamera::leftCamera, mrpt::utils::TStereoCamera::loadFromConfigFile(), mrpt::utils::CConfigFileBase::read_bool(), mrpt::utils::CConfigFileBase::read_float(), mrpt::utils::CConfigFileBase::read_int(), mrpt::utils::CConfigFileBase::read_string(), mrpt::utils::TStereoCamera::rightCamera, mrpt::utils::TStereoCamera::rightCameraPose, and mrpt::utils::CConfigFileBase::sectionExists().

Here is the call graph for this function:

◆ open()

void COpenNI2Generic::open ( unsigned  sensor_id = 0)
inherited

Try to open the camera (all the parameters [resolution,fps,...] must be set before calling this) - users may also call initialize(), which in turn calls this method.

Raises an exception upon error.

Exceptions
std::exceptionA textual description of the error.

Definition at line 257 of file COpenNI2Generic.cpp.

References mrpt::mrpt::format(), mrpt::hwdrivers::COpenNI2Generic::getNumDevices(), mrpt::hwdrivers::COpenNI2Generic::isOpen(), mrpt::hwdrivers::COpenNI2Generic::m_fps, mrpt::hwdrivers::COpenNI2Generic::m_height, mrpt::hwdrivers::COpenNI2Generic::m_verbose, mrpt::hwdrivers::COpenNI2Generic::m_width, MRPT_UNUSED_PARAM, mrpt::hwdrivers::COpenNI2Generic::showLog(), THROW_EXCEPTION, and mrpt::hwdrivers::COpenNI2Generic::vDevices.

Referenced by mrpt::hwdrivers::COpenNI2Generic::openDevicesBySerialNum().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ openDeviceBySerial()

unsigned int COpenNI2Generic::openDeviceBySerial ( const unsigned int  SerialRequired)
inherited

Open a RGBD device specified by its serial number.

This method is a wrapper for openDevicesBySerialNum(const std::set<unsigned>& vSerialRequired) This method requires to open the sensors which are still closed to read their serial.

Definition at line 356 of file COpenNI2Generic.cpp.

References mrpt::hwdrivers::COpenNI2Generic::openDevicesBySerialNum().

Here is the call graph for this function:

◆ openDevicesBySerialNum()

unsigned int COpenNI2Generic::openDevicesBySerialNum ( const std::set< unsigned > &  vSerialRequired)
inherited

Open a set of RGBD devices specified by their serial number.

Raises an exception when the demanded serial numbers are not among the connected devices. This function also fills a vector with the serial numbers of the connected OpenNI2 sensors (this requires openning the sensors which are still closed to read their serial)

Definition at line 301 of file COpenNI2Generic.cpp.

References mrpt::mrpt::format(), mrpt::hwdrivers::COpenNI2Generic::isOpen(), mrpt::hwdrivers::COpenNI2Generic::m_fps, mrpt::hwdrivers::COpenNI2Generic::m_height, mrpt::hwdrivers::COpenNI2Generic::m_verbose, mrpt::hwdrivers::COpenNI2Generic::m_width, MRPT_UNUSED_PARAM, mrpt::hwdrivers::COpenNI2Generic::open(), mrpt::hwdrivers::COpenNI2Generic::showLog(), THROW_EXCEPTION, and mrpt::hwdrivers::COpenNI2Generic::vDevices.

Referenced by mrpt::hwdrivers::COpenNI2Generic::openDeviceBySerial().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ registerClass()

void CGenericSensor::registerClass ( const TSensorClassId pNewClass)
staticinherited

Register a class into the internal list of "CGenericSensor" descendents.

Used internally in the macros DEFINE_GENERIC_SENSOR, etc...

Can be used as "CGenericSensor::registerClass( SENSOR_CLASS_ID(CMySensor) );" if building custom sensors outside mrpt libraries in user code.

Definition at line 121 of file CGenericSensor.cpp.

References mrpt::hwdrivers::TSensorClassId::className, and mrpt::hwdrivers::CGenericSensor::get_registered_sensor_classes().

Referenced by mrpt::hwdrivers::CGenericSensor::CLASSINIT_GENERIC_SENSOR::CLASSINIT_GENERIC_SENSOR().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ setCameraParamsDepth()

void mrpt::hwdrivers::COpenNI2Sensor::setCameraParamsDepth ( const mrpt::utils::TCamera p)
inline

Definition at line 318 of file COpenNI2Sensor.h.

References m_cameraParamsDepth.

◆ setCameraParamsIntensity()

void mrpt::hwdrivers::COpenNI2Sensor::setCameraParamsIntensity ( const mrpt::utils::TCamera p)
inline

Definition at line 308 of file COpenNI2Sensor.h.

References m_cameraParamsRGB.

◆ setExternalImageFormat()

void mrpt::hwdrivers::CGenericSensor::setExternalImageFormat ( const std::string ext)
inlineinherited

Set the extension ("jpg","gif","png",...) that determines the format of images saved externally The default is "jpg".

See also
setPathForExternalImages, setExternalImageJPEGQuality

Definition at line 279 of file CGenericSensor.h.

References mrpt::hwdrivers::CGenericSensor::m_external_images_format.

◆ setExternalImageJPEGQuality()

void mrpt::hwdrivers::CGenericSensor::setExternalImageJPEGQuality ( const unsigned int  quality)
inlineinherited

The quality of JPEG compression, when external images is enabled and the format is "jpg".

See also
setExternalImageFormat

Definition at line 286 of file CGenericSensor.h.

References mrpt::hwdrivers::CGenericSensor::m_external_images_jpeg_quality.

◆ setPathForExternalImages()

void COpenNI2Sensor::setPathForExternalImages ( const std::string directory)
virtual

Set the path where to save off-rawlog image files (this class DOES take into account this path).

An empty string (the default value at construction) means to save images embedded in the rawlog, instead of on separate files.

Exceptions
std::exceptionIf the directory doesn't exists and cannot be created.

Reimplemented from mrpt::hwdrivers::CGenericSensor.

Definition at line 373 of file COpenNI2Sensor.cpp.

References MRPT_UNUSED_PARAM.

◆ setRelativePoseIntensityWrtDepth()

void mrpt::hwdrivers::COpenNI2Sensor::setRelativePoseIntensityWrtDepth ( const mrpt::poses::CPose3D p)
inline

Set the pose of the intensity camera wrt the depth camera.

See also
See mrpt::obs::CObservation3DRangeScan for a 3D diagram of this pose

Definition at line 325 of file COpenNI2Sensor.h.

References m_relativePoseIntensityWRTDepth.

◆ setSensorIDToOpen()

void mrpt::hwdrivers::COpenNI2Sensor::setSensorIDToOpen ( const unsigned  sensor_id)
inline

Set the sensor_id of the device to open.

Exceptions
Thismethod must throw an exception when such serial number is not found among the connected devices.

Definition at line 245 of file COpenNI2Sensor.h.

References m_user_device_number.

◆ setSensorLabel()

void mrpt::hwdrivers::CGenericSensor::setSensorLabel ( const std::string sensorLabel)
inlineinherited

Definition at line 96 of file CGenericSensor.h.

References mrpt::hwdrivers::CGenericSensor::m_sensorLabel.

◆ setSerialToOpen()

void mrpt::hwdrivers::COpenNI2Sensor::setSerialToOpen ( const unsigned  serial)
inline

Set the serial number of the device to open.

Exceptions
Thismethod must throw an exception when such serial number is not found among the connected devices.

Definition at line 236 of file COpenNI2Sensor.h.

References m_serial_number.

◆ setVerbose()

void COpenNI2Generic::setVerbose ( bool  verbose)
inherited

Definition at line 149 of file COpenNI2Generic.cpp.

References mrpt::hwdrivers::COpenNI2Generic::m_verbose.

◆ showLog()

void COpenNI2Generic::showLog ( const std::string message) const
protectedinherited

◆ start()

bool COpenNI2Generic::start ( )
inherited

Open all sensor streams (normally called automatically at constructor, no need to call it manually).

Returns
false on error
See also
kill() to close

Definition at line 114 of file COpenNI2Generic.cpp.

References mrpt::hwdrivers::COpenNI2Generic::numInstances, and THROW_EXCEPTION.

Referenced by mrpt::hwdrivers::COpenNI2Generic::COpenNI2Generic().

Here is the caller graph for this function:

Member Data Documentation

◆ m_cameraParamsDepth

mrpt::utils::TCamera mrpt::hwdrivers::COpenNI2Sensor::m_cameraParamsDepth
protected

Params for the Depth camera.

Definition at line 369 of file COpenNI2Sensor.h.

Referenced by getCameraParamsDepth(), and setCameraParamsDepth().

◆ m_cameraParamsRGB

mrpt::utils::TCamera mrpt::hwdrivers::COpenNI2Sensor::m_cameraParamsRGB
protected

Params for the RGB camera.

Definition at line 366 of file COpenNI2Sensor.h.

Referenced by getCameraParamsIntensity(), getColCount(), getRowCount(), and setCameraParamsIntensity().

◆ m_depth_format

int mrpt::hwdrivers::COpenNI2Generic::m_depth_format
protectedinherited

◆ m_external_images_format

std::string mrpt::hwdrivers::CGenericSensor::m_external_images_format
protectedinherited

The extension ("jpg","gif","png",...) that determines the format of images saved externally.

See also
setPathForExternalImages

Definition at line 158 of file CGenericSensor.h.

Referenced by mrpt::hwdrivers::CSwissRanger3DCamera::getNextObservation(), mrpt::hwdrivers::CSwissRanger3DCamera::loadConfig_sensorSpecific(), and mrpt::hwdrivers::CGenericSensor::setExternalImageFormat().

◆ m_external_images_jpeg_quality

unsigned int mrpt::hwdrivers::CGenericSensor::m_external_images_jpeg_quality
protectedinherited

◆ m_fps

float mrpt::hwdrivers::COpenNI2Generic::m_fps
protectedinherited

◆ m_grab_3D_points

bool mrpt::hwdrivers::COpenNI2Generic::m_grab_3D_points
protectedinherited

Definition at line 163 of file COpenNI2Generic.h.

Referenced by enableGrab3DPoints(), and isGrab3DPointsEnabled().

◆ m_grab_decimation

size_t mrpt::hwdrivers::CGenericSensor::m_grab_decimation
protectedinherited

If set to N>=2, only 1 out of N observations will be saved to m_objList.

Definition at line 139 of file CGenericSensor.h.

Referenced by mrpt::hwdrivers::CGenericSensor::appendObservations(), and mrpt::hwdrivers::CGenericSensor::loadConfig().

◆ m_grab_decimation_counter

size_t mrpt::hwdrivers::CGenericSensor::m_grab_decimation_counter
protectedinherited

Used when "m_grab_decimation" is enabled.

Definition at line 146 of file CGenericSensor.h.

Referenced by mrpt::hwdrivers::CGenericSensor::appendObservations(), and mrpt::hwdrivers::CGenericSensor::loadConfig().

◆ m_grab_depth

bool mrpt::hwdrivers::COpenNI2Generic::m_grab_depth
protectedinherited

Definition at line 163 of file COpenNI2Generic.h.

Referenced by enableGrabDepth(), and isGrabDepthEnabled().

◆ m_grab_image

bool mrpt::hwdrivers::COpenNI2Generic::m_grab_image
protectedinherited

The data that the RGBD sensors can return.

Default: all true

Definition at line 163 of file COpenNI2Generic.h.

Referenced by enableGrabRGB(), and isGrabRGBEnabled().

◆ m_height

int mrpt::hwdrivers::COpenNI2Generic::m_height
protectedinherited

◆ m_max_queue_len

size_t mrpt::hwdrivers::CGenericSensor::m_max_queue_len
protectedinherited

See CGenericSensor.

Definition at line 136 of file CGenericSensor.h.

Referenced by mrpt::hwdrivers::CGenericSensor::loadConfig().

◆ m_maxRange

double mrpt::hwdrivers::COpenNI2Sensor::m_maxRange
protected

Sensor max range (meters)

Definition at line 376 of file COpenNI2Sensor.h.

Referenced by getMaxRange().

◆ m_path_for_external_images

std::string mrpt::hwdrivers::CGenericSensor::m_path_for_external_images
protectedinherited

The path where to save off-rawlog images: empty means save images embedded in the rawlog.

Definition at line 155 of file CGenericSensor.h.

Referenced by mrpt::hwdrivers::CSwissRanger3DCamera::getNextObservation(), and mrpt::hwdrivers::CSwissRanger3DCamera::setPathForExternalImages().

◆ m_preview_decim_counter_range

size_t mrpt::hwdrivers::COpenNI2Sensor::m_preview_decim_counter_range
protected

Definition at line 361 of file COpenNI2Sensor.h.

◆ m_preview_decim_counter_rgb

size_t mrpt::hwdrivers::COpenNI2Sensor::m_preview_decim_counter_rgb
protected

Definition at line 361 of file COpenNI2Sensor.h.

◆ m_preview_window

bool mrpt::hwdrivers::COpenNI2Sensor::m_preview_window
protected

Show preview window while grabbing.

Definition at line 357 of file COpenNI2Sensor.h.

◆ m_preview_window_decimation

size_t mrpt::hwdrivers::COpenNI2Sensor::m_preview_window_decimation
protected

If preview is enabled, only show 1 out of N images.

Definition at line 360 of file COpenNI2Sensor.h.

◆ m_process_rate

double mrpt::hwdrivers::CGenericSensor::m_process_rate
protectedinherited

◆ m_relativePoseIntensityWRTDepth

mrpt::poses::CPose3D mrpt::hwdrivers::COpenNI2Sensor::m_relativePoseIntensityWRTDepth
protected

See mrpt::obs::CObservation3DRangeScan for a diagram of this pose.

Definition at line 372 of file COpenNI2Sensor.h.

Referenced by getRelativePoseIntensityWrtDepth(), and setRelativePoseIntensityWrtDepth().

◆ m_rgb_format

int mrpt::hwdrivers::COpenNI2Generic::m_rgb_format
protectedinherited

◆ m_sensorLabel

std::string mrpt::hwdrivers::CGenericSensor::m_sensorLabel
protectedinherited

See CGenericSensor.

Definition at line 141 of file CGenericSensor.h.

Referenced by mrpt::hwdrivers::CCANBusReader::CCANBusReader(), mrpt::hwdrivers::CGPSInterface::CGPSInterface(), mrpt::hwdrivers::CGyroKVHDSP3000::CGyroKVHDSP3000(), mrpt::hwdrivers::CHokuyoURG::CHokuyoURG(), mrpt::hwdrivers::CIMUIntersense::CIMUIntersense(), mrpt::hwdrivers::CIMUXSens::CIMUXSens(), mrpt::hwdrivers::CIMUXSens_MT4::CIMUXSens_MT4(), mrpt::hwdrivers::CKinect::CKinect(), mrpt::hwdrivers::CNationalInstrumentsDAQ::CNationalInstrumentsDAQ(), mrpt::hwdrivers::CRoboPeakLidar::CRoboPeakLidar(), mrpt::hwdrivers::CSickLaserSerial::CSickLaserSerial(), mrpt::hwdrivers::CSickLaserUSB::CSickLaserUSB(), mrpt::hwdrivers::CSkeletonTracker::CSkeletonTracker(), mrpt::hwdrivers::CSwissRanger3DCamera::CSwissRanger3DCamera(), mrpt::hwdrivers::CVelodyneScanner::CVelodyneScanner(), mrpt::hwdrivers::CIMUXSens_MT4::doProcess(), mrpt::hwdrivers::CIMUXSens::doProcess(), mrpt::hwdrivers::CGyroKVHDSP3000::doProcess(), mrpt::hwdrivers::CIMUIntersense::doProcess(), mrpt::hwdrivers::CSkeletonTracker::doProcess(), mrpt::hwdrivers::CRoboPeakLidar::doProcessSimple(), mrpt::hwdrivers::CSickLaserUSB::doProcessSimple(), mrpt::hwdrivers::CCANBusReader::doProcessSimple(), mrpt::hwdrivers::CHokuyoURG::doProcessSimple(), mrpt::hwdrivers::CSickLaserSerial::doProcessSimple(), mrpt::hwdrivers::CGPSInterface::flushParsedMessagesNow(), mrpt::hwdrivers::CSwissRanger3DCamera::getNextObservation(), mrpt::hwdrivers::CKinect::getNextObservation(), mrpt::hwdrivers::CVelodyneScanner::getNextObservation(), mrpt::hwdrivers::CGenericSensor::getSensorLabel(), mrpt::hwdrivers::CNationalInstrumentsDAQ::grabbing_thread(), mrpt::hwdrivers::CGenericSensor::loadConfig(), mrpt::hwdrivers::CSkeletonTracker::processPreview(), mrpt::hwdrivers::C2DRangeFinderAbstract::processPreview(), mrpt::hwdrivers::CSkeletonTracker::processPreviewNone(), and mrpt::hwdrivers::CGenericSensor::setSensorLabel().

◆ m_sensorPoseOnRobot

mrpt::poses::CPose3D mrpt::hwdrivers::COpenNI2Sensor::m_sensorPoseOnRobot
protected

Definition at line 353 of file COpenNI2Sensor.h.

◆ m_serial_number

int mrpt::hwdrivers::COpenNI2Sensor::m_serial_number
protected

Serial number of device to open.

Definition at line 383 of file COpenNI2Sensor.h.

Referenced by setSerialToOpen().

◆ m_state

TSensorState mrpt::hwdrivers::CGenericSensor::m_state
protectedinherited

◆ m_user_device_number

int mrpt::hwdrivers::COpenNI2Sensor::m_user_device_number
protected

Number of device to open (0:first,...)

Definition at line 380 of file COpenNI2Sensor.h.

Referenced by setSensorIDToOpen().

◆ m_verbose [1/2]

bool mrpt::hwdrivers::CGenericSensor::m_verbose
protectedinherited

◆ m_verbose [2/2]

bool mrpt::hwdrivers::COpenNI2Generic::m_verbose
protectedinherited

◆ m_width

int mrpt::hwdrivers::COpenNI2Generic::m_width
protectedinherited

The same options (width, height and fps) are set for all the sensors.

(This could be changed if necessary)

Definition at line 155 of file COpenNI2Generic.h.

Referenced by mrpt::hwdrivers::COpenNI2Generic::open(), and mrpt::hwdrivers::COpenNI2Generic::openDevicesBySerialNum().

◆ m_win_int

mrpt::gui::CDisplayWindow::Ptr mrpt::hwdrivers::COpenNI2Sensor::m_win_int
protected

Definition at line 362 of file COpenNI2Sensor.h.

◆ m_win_range

mrpt::gui::CDisplayWindow::Ptr mrpt::hwdrivers::COpenNI2Sensor::m_win_range
protected

Definition at line 362 of file COpenNI2Sensor.h.

◆ numInstances

int COpenNI2Generic::numInstances = 0
staticprotectedinherited

◆ vDevices

std::vector< std::shared_ptr< COpenNI2Generic::CDevice > > COpenNI2Generic::vDevices
staticprotectedinherited

◆ vSerialNums

std::vector<int> mrpt::hwdrivers::COpenNI2Generic::vSerialNums
protectedinherited

A vector with the serial numbers of the available devices.

Definition at line 151 of file COpenNI2Generic.h.




Page generated by Doxygen 1.8.14 for MRPT 1.9.9 Git: ae4571287 Thu Nov 23 00:06:53 2017 +0100 at dom oct 27 23:51:55 CET 2019