NDEVR
API Documentation
RealSenseScanner.h
1#pragma once
2#include "DLLInfo.h"
3#include "RealSenseIOSettings.h"
4#include "RasterPointScanner/Headers/RasterFrame.h"
5#include "RasterPointScanner/Headers/RasterScanner.h"
6#include "PointScanner/Headers/Scanner3D.h"
7#include "BlockModel/Headers/SegmentedBlockModel.h"
8#include "Design/Headers/PolarPointFilter.h"
9#include "Design/Headers/Camera.h"
10#include "Base/Headers/Time.h"
11#include "Base/Headers/Pointer.hpp"
12#include "Base/Headers/Thread.h"
13#include "Base/Headers/INIInterface.h"
14#include <QObject>
15#include <librealsense2/rs.hpp>
16class ScannerDriver;
17namespace rs2
18{
19 class device;
20 class video_stream_profile;
21}
22namespace NDEVR
23{
24 struct FileRequest;
25 class OrbSLAM;
26 class SLAMEngine;
28 class Log;
29 class RealSenseMotor;
31 class Battery;
32 template<class t_type, class t_smooth_type>
33 class PointSmootherBlockFilter;
34 class RealSenseOrientationSensor;
35 class RealSenseRangeSensor;
37 template<class t_type>
39 class ColorNode;
52 class RealSenseIOSettings;
59 class REALSENSE_INTERFACE_API RealSenseScanner : public RasterScanner
60 {
61 public:
62 static constexpr const char* const fw_version = "Firmware/D4XX_FW_Image-5.16.0.1.bin";
69 RealSenseScanner(Model& model, RealSenseScannerConnection* connection, DesignObjectLookup* manager, QObject* parent = nullptr);
81 RealSenseScanner(UUID id, DesignObjectLookup* manager, QObject* parent = nullptr);
88 [[nodiscard]] virtual Motor* headMotor(uint01 axis) const override;
92 [[nodiscard]] uint04 meshBlendFactor() const override { return 1U; }
96 void setupRSStream(const RealSenseIOSettings& settings);
104 [[nodiscard]] Vector<3, Angle<fltp08>> headAngle() const override;
108 virtual void orientHead(const Vector<3, Angle<fltp08>>& head_orientation) override;
112 [[nodiscard]] virtual Connection* connection() const override;
114 void setupCameraModel() override;
122 void updateFW(File fw_file);
126 void updateFW(const Buffer<uint01>& fw_data);
130 virtual bool isOrientationValid() const override;
131 protected:
142 void setupSLAM(const rs2::sensor& sensor, const rs2::video_stream_profile& video_profile, const rs2::video_stream_profile& depth, rs2::stream_profile gyro);
144 void updateIOState() override;
148 virtual FileRequest scanModelFile() const override;
152 virtual Matrix<fltp08> scanModelFileTransform() const override;
156 virtual void update(Time time) override;
161 bool processFrame(const rs2::frame& frame);
167 bool collectPoints() override;
168 protected:
172 bool attemptConnection() override;
173 protected:
174 rs2::frameset m_frame_set;
175 rs2::syncer* m_syncer = nullptr;
176 fltp08 m_last_collect_time = Constant<fltp08>::Invalid;
180 rs2::frameset m_rs_frame;
182 rs2::device m_rs_device;
186 fltp04 m_usb_version = Constant<fltp04>::Invalid;
189 bool m_has_imu = false;
190 };
191}
Stores an angle in an optimized internal format with support for efficient trigonometric operations.
Definition Angle.h:83
A device which has an associated voltage or percent that changes.
Definition Battery.h:106
The equivelent of std::vector but with a bit more control.
Definition Buffer.hpp:58
A standard interface for all types of connections that allow transmitting and receiving of data betwe...
Definition Connection.h:316
A core class where all Design Objects including models, materials, and geometries are stored.
Logic for reading or writing to a file as well as navigating filesystems or other common file operati...
Definition File.h:53
Serves as the primary program interface for processes to report issues and allows any number of LogSt...
Definition Log.h:50
Templated logic for doing matrix multiplication.
Definition Matrix.hpp:182
A core class that represents a node on model hierarchy.
Definition Model.h:292
A motor is a device which produces rotational spin.
Definition Motor.h:46
Main entry point for the ORB-SLAM3 system.
Definition System.h:37
Aggregated IO settings for all RealSense streams and laser configuration.
Device that manages a pair of RealSenseMotor servo axes for a scanning mount.
Motor controller for a single servo axis on a RealSense scanning mount.
Point smoother specialized for RealSense camera intrinsics.
Position sensor implementation using RealSense T265 tracking or SLAM-derived poses.
Connection subclass for a locally or remotely connected RealSense device.
bool attemptConnection() override
Attempts to establish a connection to the RealSense device.
void updateFW(const Buffer< uint01 > &fw_data)
Updates the device firmware from a data buffer.
fltp04 m_usb_version
The USB version of the connection.
void updateFW(File fw_file)
Updates the device firmware from a file.
uint01 * m_swap_buffer
Temporary buffer for data swapping.
rs2::frameset m_rs_frame
The most recent raw RealSense frameset.
bool collectPoints() override
Collects points from the current depth frame.
rs2::device m_rs_device
The underlying RealSense device handle.
bool m_has_imu
Whether the device has an IMU.
void updateIOState() override
Updates the IO state (stream settings) if changes are pending.
virtual bool isOrientationValid() const override
Returns whether the orientation sensor data is valid.
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.
RealSenseIOSettings m_active_io_settings
The currently active IO settings.
void startRSStream(RealSenseIOSettings settings)
Starts RealSense streaming with the given settings.
virtual Motor * headMotor(uint01 axis) const override
Returns the motor for a given head axis.
bool m_align_to_depth_frame
Whether to align color to depth frame.
virtual Connection * connection() const override
Returns the connection for this scanner.
bool m_rs_streaming_active
Whether RealSense streaming is active.
bool processFrame(const rs2::frame &frame)
Processes a single RealSense frame (depth, color, IMU, etc.).
virtual void orientHead(const Vector< 3, Angle< fltp08 > > &head_orientation) override
Moves the scanner head to the specified orientation.
uint04 meshBlendFactor() const override
Returns the mesh blend factor for point cloud meshing.
fltp08 m_last_collect_time
Timestamp of last point collection.
void initDevice()
Initializes the RealSense device and queries capabilities.
virtual void update(Time time) override
Performs a periodic update tick.
void setupCameraModel() override
Sets up the 3D camera model for visualization.
RealSenseIOSettings m_requested_io_settings
The IO settings requested by the user.
void setupRSStream(const RealSenseIOSettings &settings)
Configures the RealSense streams without starting them.
Vector< 3, Angle< fltp08 > > headAngle() const override
Returns the current head angle from the motor manager.
File m_firmware_file
Path to firmware file for updates.
RealSenseScannerConnection * m_connection
The device connection.
void setDeviceType(RealSenseDeviceType device)
Sets the device type for this scanner.
virtual FileRequest scanModelFile() const override
Returns the file request for the scanner 3D model.
RealSenseScanner(UUID id, DesignObjectLookup *manager, QObject *parent=nullptr)
Constructs a remote scanner by UUID.
rs2::frameset m_frame_set
The current synced frameset.
bool finishActiveFrame()
Finalizes the active frame and publishes the point cloud.
virtual Matrix< fltp08 > scanModelFileTransform() const override
Returns the transformation matrix for the scanner 3D model.
rs2::syncer * m_syncer
Frame synchronizer for multi-stream alignment.
RealSenseScanner(RealSenseScannerConnection *connection, DesignObjectLookup *manager, QObject *parent=nullptr)
Constructs a scanner from a connection (creates its own model).
RealSenseMotorManager * m_motor_manager
The motor manager for head control.
RealSenseScanner(Model &model, RealSenseScannerConnection *connection, DesignObjectLookup *manager, QObject *parent=nullptr)
Constructs a scanner from an existing model and connection.
RealSenseDeviceType m_device_type
The detected device type.
virtual ~RealSenseScanner()
Destroys the scanner and releases all resources.
static constexpr const char *const fw_version
Expected firmware version path.
Provides logic to perform SLAM on an object.
Definition SLAMEngine.h:31
A Model subclass providing a segmented spatial block model over a bounded region.
Represents a timestamp with utilities for manipulation and conversion.
Definition Time.h:62
A universally unique identifier (UUID) is a 128-bit number used to identify information in computer s...
Definition UUID.h:61
A fixed-size array with N dimensions used as the basis for geometric and mathematical types.
Definition Vector.hpp:62
The primary namespace for the NDEVR SDK.
float fltp04
Defines an alias representing a 4 byte floating-point number Bit layout is as follows: -Sign: 1 bit a...
uint32_t uint04
-Defines an alias representing a 4 byte, unsigned integer -Can represent exact integer values 0 throu...
double fltp08
Defines an alias representing an 8 byte floating-point number.
uint8_t uint01
-Defines an alias representing a 1 byte, unsigned integer -Can represent exact integer values 0 throu...
RealSenseDeviceType
Enumeration of supported RealSense device types.
@ e_d455
Intel RealSense D455.
@ e_t265
Intel RealSense T265 tracking camera.
@ e_d457
Intel RealSense D457.
@ e_d435
Intel RealSense D435.
@ e_d405
Intel RealSense D405.
@ e_unknown
Unknown device type.
A FileRequest bundles format data as well as a particular file.
Definition FileFormat.h:101