NDEVR
API Documentation
RealSenseScanner

3D scanner implementation for Intel RealSense depth cameras. More...

Collaboration diagram for RealSenseScanner:
[legend]

Public Member Functions

 RealSenseScanner (Model &model, RealSenseScannerConnection *connection, DesignObjectLookup *manager, QObject *parent=nullptr)
 Constructs a scanner from an existing model and connection.
 RealSenseScanner (RealSenseScannerConnection *connection, DesignObjectLookup *manager, QObject *parent=nullptr)
 Constructs a scanner from a connection (creates its own model).
 RealSenseScanner (UUID id, DesignObjectLookup *manager, QObject *parent=nullptr)
 Constructs a remote scanner by UUID.
virtual ~RealSenseScanner ()
 Destroys the scanner and releases all resources.
virtual Connectionconnection () const override
 Returns the connection for this scanner.
Vector< 3, Angle< fltp08 > > headAngle () const override
 Returns the current head angle from the motor manager.
virtual MotorheadMotor (uint01 axis) const override
 Returns the motor for a given head axis.
virtual bool isOrientationValid () const override
 Returns whether the orientation sensor data is valid.
uint04 meshBlendFactor () const override
 Returns the mesh blend factor for point cloud meshing.
virtual void orientHead (const Vector< 3, Angle< fltp08 > > &head_orientation) override
 Moves the scanner head to the specified orientation.
void setDeviceType (RealSenseDeviceType device)
 Sets the device type for this scanner.
void setupCameraModel () override
 Sets up the 3D camera model for visualization.
void setupRSStream (const RealSenseIOSettings &settings)
 Configures the RealSense streams without starting them.
void startRSStream (RealSenseIOSettings settings)
 Starts RealSense streaming with the given settings.
void updateFW (const Buffer< uint01 > &fw_data)
 Updates the device firmware from a data buffer.
void updateFW (File fw_file)
 Updates the device firmware from a file.

Static Public Attributes

static constexpr const char *const fw_version = "Firmware/D4XX_FW_Image-5.16.0.1.bin"
 Expected firmware version path.

Protected Member Functions

bool attemptConnection () override
 Attempts to establish a connection to the RealSense device.
bool collectPoints () override
 Collects points from the current depth frame.
bool finishActiveFrame ()
 Finalizes the active frame and publishes the point cloud.
void initDevice ()
 Initializes the RealSense device and queries capabilities.
bool processFrame (const rs2::frame &frame)
 Processes a single RealSense frame (depth, color, IMU, etc.).
virtual FileRequest scanModelFile () const override
 Returns the file request for the scanner 3D model.
virtual Matrix< fltp08scanModelFileTransform () const override
 Returns the transformation matrix for the scanner 3D model.
void setupSLAM (const rs2::sensor &sensor, const rs2::video_stream_profile &video_profile, const rs2::video_stream_profile &depth, rs2::stream_profile gyro)
 Sets up the SLAM engine for visual-inertial tracking.
virtual void update (Time time) override
 Performs a periodic update tick.
void updateIOState () override
 Updates the IO state (stream settings) if changes are pending.

Protected Attributes

RealSenseIOSettings m_active_io_settings
 The currently active IO settings.
bool m_align_to_depth_frame = false
 Whether to align color to depth frame.
RealSenseScannerConnectionm_connection = nullptr
 The device connection.
RealSenseDeviceType m_device_type = RealSenseDeviceType::e_unknown
 The detected device type.
File m_firmware_file
 Path to firmware file for updates.
rs2::frameset m_frame_set
 The current synced frameset.
bool m_has_imu = false
 Whether the device has an IMU.
fltp08 m_last_collect_time = Constant<fltp08>::Invalid
 Timestamp of last point collection.
RealSenseMotorManagerm_motor_manager = nullptr
 The motor manager for head control.
RealSenseIOSettings m_requested_io_settings
 The IO settings requested by the user.
rs2::device m_rs_device
 The underlying RealSense device handle.
rs2::frameset m_rs_frame
 The most recent raw RealSense frameset.
bool m_rs_streaming_active = false
 Whether RealSense streaming is active.
uint01m_swap_buffer = nullptr
 Temporary buffer for data swapping.
rs2::syncer * m_syncer = nullptr
 Frame synchronizer for multi-stream alignment.
fltp04 m_usb_version = Constant<fltp04>::Invalid
 The USB version of the connection.

Detailed Description

3D scanner implementation for Intel RealSense depth cameras.

Manages RealSense device streaming, point cloud collection, SLAM integration, firmware updates, and optional motorized head control.

Definition at line 59 of file RealSenseScanner.h.

Constructor & Destructor Documentation

◆ RealSenseScanner() [1/3]

RealSenseScanner::RealSenseScanner ( Model & model,
RealSenseScannerConnection * connection,
DesignObjectLookup * manager,
QObject * parent = nullptr )

Constructs a scanner from an existing model and connection.

Parameters
[in]modelThe design model for this scanner.
[in]connectionThe RealSense device connection.
[in]managerThe design object lookup.
[in]parentOptional parent QObject.

References connection().

◆ RealSenseScanner() [2/3]

RealSenseScanner::RealSenseScanner ( RealSenseScannerConnection * connection,
DesignObjectLookup * manager,
QObject * parent = nullptr )

Constructs a scanner from a connection (creates its own model).

Parameters
[in]connectionThe RealSense device connection.
[in]managerThe design object lookup.
[in]parentOptional parent QObject.

References connection().

◆ RealSenseScanner() [3/3]

RealSenseScanner::RealSenseScanner ( UUID id,
DesignObjectLookup * manager,
QObject * parent = nullptr )

Constructs a remote scanner by UUID.

Parameters
[in]idThe UUID of the remote scanner.
[in]managerThe design object lookup.
[in]parentOptional parent QObject.

Member Function Documentation

◆ attemptConnection()

bool RealSenseScanner::attemptConnection ( )
overrideprotected

Attempts to establish a connection to the RealSense device.

Returns
True if the connection was successful.

◆ collectPoints()

bool RealSenseScanner::collectPoints ( )
overrideprotected

Collects points from the current depth frame.

Returns
True if points were collected.

◆ connection()

virtual Connection * RealSenseScanner::connection ( ) const
nodiscardoverridevirtual

Returns the connection for this scanner.

Returns
A pointer to the connection.

Referenced by RealSenseScanner(), and RealSenseScanner().

◆ finishActiveFrame()

bool RealSenseScanner::finishActiveFrame ( )
protected

Finalizes the active frame and publishes the point cloud.

Returns
True if a frame was successfully finished.

◆ headAngle()

Vector< 3, Angle< fltp08 > > RealSenseScanner::headAngle ( ) const
nodiscardoverride

Returns the current head angle from the motor manager.

Returns
A 3D vector of angles (pan, tilt, roll).

◆ headMotor()

virtual Motor * RealSenseScanner::headMotor ( uint01 axis) const
nodiscardoverridevirtual

Returns the motor for a given head axis.

Parameters
[in]axisThe axis index.
Returns
A pointer to the motor, or nullptr.

◆ isOrientationValid()

virtual bool RealSenseScanner::isOrientationValid ( ) const
overridevirtual

Returns whether the orientation sensor data is valid.

Returns
True if orientation is valid.

◆ meshBlendFactor()

uint04 RealSenseScanner::meshBlendFactor ( ) const
inlinenodiscardoverride

Returns the mesh blend factor for point cloud meshing.

Returns
Always returns 1.

Definition at line 92 of file RealSenseScanner.h.

◆ orientHead()

virtual void RealSenseScanner::orientHead ( const Vector< 3, Angle< fltp08 > > & head_orientation)
overridevirtual

Moves the scanner head to the specified orientation.

Parameters
[in]head_orientationThe target orientation angles.

◆ processFrame()

bool RealSenseScanner::processFrame ( const rs2::frame & frame)
protected

Processes a single RealSense frame (depth, color, IMU, etc.).

Parameters
[in]frameThe RealSense frame to process.
Returns
True if the frame was successfully processed.

◆ scanModelFile()

virtual FileRequest RealSenseScanner::scanModelFile ( ) const
overrideprotectedvirtual

Returns the file request for the scanner 3D model.

Returns
The model file request.

◆ scanModelFileTransform()

virtual Matrix< fltp08 > RealSenseScanner::scanModelFileTransform ( ) const
overrideprotectedvirtual

Returns the transformation matrix for the scanner 3D model.

Returns
The model file transform matrix.

◆ setDeviceType()

void RealSenseScanner::setDeviceType ( RealSenseDeviceType device)

Sets the device type for this scanner.

Parameters
[in]deviceThe RealSense device type.

◆ setupRSStream()

void RealSenseScanner::setupRSStream ( const RealSenseIOSettings & settings)

Configures the RealSense streams without starting them.

Parameters
[in]settingsThe stream settings to configure.

◆ setupSLAM()

void RealSenseScanner::setupSLAM ( const rs2::sensor & sensor,
const rs2::video_stream_profile & video_profile,
const rs2::video_stream_profile & depth,
rs2::stream_profile gyro )
protected

Sets up the SLAM engine for visual-inertial tracking.

Parameters
[in]sensorThe RealSense sensor providing video data.
[in]video_profileThe video stream profile for SLAM input.
[in]depthThe depth stream profile.
[in]gyroThe gyroscope stream profile.

◆ startRSStream()

void RealSenseScanner::startRSStream ( RealSenseIOSettings settings)

Starts RealSense streaming with the given settings.

Parameters
[in]settingsThe stream settings to start with.

◆ update()

virtual void RealSenseScanner::update ( Time time)
overrideprotectedvirtual

Performs a periodic update tick.

Parameters
[in]timeThe current system time.

◆ updateFW() [1/2]

void RealSenseScanner::updateFW ( const Buffer< uint01 > & fw_data)

Updates the device firmware from a data buffer.

Parameters
[in]fw_dataThe firmware binary data.

◆ updateFW() [2/2]

void RealSenseScanner::updateFW ( File fw_file)

Updates the device firmware from a file.

Parameters
[in]fw_fileThe firmware file to flash.

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