35#include <NDEVR/Device.h>
36#include <NDEVR/PointScannerOptions.h>
37#include <NDEVR/MaterialRaster.h>
38#include <NDEVR/SnapLocation.h>
39#include <NDEVR/Scan.h>
40#include <NDEVR/Matrix.h>
41#include <NDEVR/UUID.h>
42#include <NDEVR/Time.h>
43#include <NDEVR/Plane.h>
44#include <NDEVR/Pointer.h>
45#include <NDEVR/Vector.h>
86 enum class ScanPointType
89 , e_calibrate_circle_a
90 , e_calibrate_circle_b
91 , e_calibrate_circle_c
96 struct ScanSpeedProfile
99 ScanSpeedProfile(TranslatedString title, fltp04 speed)
103 TranslatedString title;
109 struct PolarScanResolutionInfo
111 Bounds<2, Angle<fltp08>> bounds;
112 Vector<2, Angle<fltp08>> step = Vector<2, Angle<fltp08>>(Angle<fltp08>(DEGREES, 2.0));
118 struct CartesianScanResolutionInfo
120 Bounds<3, fltp08> bounds = Bounds<3, fltp08>(-100.0, 100.0);
121 Vector<2, fltp08> step = Vector<2, fltp08>(0.01);
127 enum ScanResolutionType
138 UUID
id = Constant<UUID>::Invalid;
139 TranslatedString title;
142 Buffer<ScanSpeedProfile> scan_speed_profiles;
143 ScanResolutionType scan_resolution_type = ScanResolutionType::e_polar;
144 CartesianScanResolutionInfo cartesian_scan_info;
145 PolarScanResolutionInfo polar_scan_info;
146 bool editable_bounds =
true;
147 bool editable_step =
true;
148 bool supports_raster =
false;
149 bool editable_raster =
false;
150 bool is_deployment_scan =
false;
151 bool is_stationary_scan =
true;
152 bool force_camera_visible =
false;
153 bool request_custom_camera_profile =
false;
154 bool force_video_record =
false;
155 bool no_point_collection =
false;
156 bool is_global_bounds =
false;
157 bool prefer_large_scanner_camera =
false;
163 struct POINT_SCANNER_API Scanner3DScanSettings
165 UUID scan_profile_id;
168 RasterInfo raster_info;
169 CartesianScanResolutionInfo cartesian_scan_info;
170 PolarScanResolutionInfo polar_scan_info;
171 bool is_child_of_station =
true;
172 void logInfo(LogPtr log)
const;
177 struct ActiveScanStatus
179 TranslatedString status_message;
181 TimeSpan time_remaining = Constant<TimeSpan>::Invalid;
183 RGBColor status_color = Constant<RGBColor>::Invalid;
184 fltp04 percent = Constant<fltp04>::Invalid;
185 bool show_status =
false;
195 class POINT_SCANNER_API Scanner3D :
public Device
199 Scanner3D(DesignObjectLookup* lookup,
const Model& model, LogPtr log, QObject* parent =
nullptr);
202 virtual void createScanner() = 0;
203 virtual void parkDevice() {}
204 [[nodiscard]]
virtual Matrix<fltp08> scanModelFileTransform()
const = 0;
205 [[nodiscard]]
virtual Matrix<fltp08> prismModelFileTransform()
const;
206 [[nodiscard]]
virtual bool supportsState(ScannerState state)
const;
207 virtual void startScan(
const Scanner3DScanSettings& settings) = 0;
208 [[nodiscard]]
virtual Buffer<ScanProfile> availableScanProfiles()
const = 0;
209 [[nodiscard]]
virtual ScanProfile scanProfile(UUID
id)
const;
210 [[nodiscard]]
virtual Plane<3, fltp08> scanPlane(
const ScanProfile& profile, uint01 dimension)
const;
211 [[nodiscard]]
virtual Vertex<3, fltp08> scanOrigin(
const ScanProfile& profile, uint01 dimension)
const;
213 virtual void addImageToRaster(
const ImageData& data,
const Vector<2, Angle<sint04>>& fov,
const Matrix<fltp08>& camera_matrix);
214 virtual void addCameraDrapeFunction(
const StringView&
id, std::function<
void()> function);
215 virtual void removeCameraDrapeFunction(
const StringView&
id);
216 [[nodiscard]] ActiveScanStatus scanStatus()
const {
return m_scan_status; };
217 [[nodiscard]]
virtual RasterInfo defaultRasterInfo(
const UUID& profile)
const;
218 [[nodiscard]]
virtual bool supportsScanImageRaster()
const {
return false; }
220 [[nodiscard]]
virtual bool rollLocked()
const {
return false; }
221 virtual bool requestRollLock(
bool) {
return false; }
223 [[nodiscard]]
virtual bool isScanning()
const {
return m_is_scanning; }
224 [[nodiscard]]
virtual bool isPaused()
const {
return m_is_paused; };
225 [[nodiscard]]
virtual ScannerState scannerState()
const {
return m_scanner_state; }
226 [[nodiscard]]
virtual Vector<3, Angle<fltp08>> headAngle()
const;
227 [[nodiscard]]
virtual Vector<3, Angle<fltp08>> pointToHeadAngle(Vertex<3, fltp08> point)
const;
229 [[nodiscard]]
virtual Motor* headMotor(uint01 axis)
const;
230 virtual void orientHead(
const Vector<3, Angle<fltp08>>& head_orientation);
231 [[nodiscard]]
virtual RangeSensor* createRangeSensor();
232 virtual void setCameraPointTarget(
const Vector<3, fltp08>& target);
233 virtual void clearCameraTarget();
234 virtual void updateCameraTarget();
235 virtual void deployStabalizer(
bool stabalizer);
236 virtual bool supportsStabalizer()
const {
return false; }
237 Vertex<3, fltp08> cameraTarget()
const;
238 virtual void endUpdates() { };
239 [[nodiscard]]
virtual UUID camera()
const {
return m_camera; }
240 [[nodiscard]]
virtual Matrix<fltp08> cameraTransform()
const {
return Matrix<fltp08>(1.0); }
241 [[nodiscard]]
virtual bool useCalibratedScan()
const {
return false; };
242 [[nodiscard]]
virtual TranslatedString scannerInfo()
const;
243 [[nodiscard]]
virtual Matrix<fltp08> scannerMatrix()
const;
244 virtual bool snapViewportToScanner()
const;
246 [[nodiscard]] PointScannerOptions& options();
247 [[nodiscard]]
const PointScannerOptions& options()
const;
249 [[nodiscard]]
virtual TimeSpan getScanTime(
const Scanner3DScanSettings&)
const {
return Constant<TimeSpan>::Invalid; };
250 [[nodiscard]]
bool pauseRequested()
const {
return m_request_pause_scan; }
251 [[nodiscard]]
bool startRequested()
const {
return m_request_start_scan; }
252 [[nodiscard]]
bool stopRequested()
const {
return m_request_stop_scan; }
254 virtual bool executeManualCommand(
const String& command) { UNUSED(command);
return false; };
255 virtual void recordPoint(
bool record_to_cloud =
true,
bool record_to_mesh =
true);
256 virtual void recordPoint(
const PolarScanRecord<fltp04>& record);
257 virtual void setScannerState(ScannerState scanner_state);
258 virtual void requestConnect();
259 virtual void requestDisconnect();
260 virtual void requestStopScan();
261 virtual void requestResumeScan();
262 virtual void requestPauseScan();
263 virtual uint04 meshBlendFactor()
const {
return 3U; }
264 [[nodiscard]]
virtual DynamicPointer<Scan> scan();
265 [[nodiscard]]
virtual Buffer<Battery*> batteries()
const {
return Buffer<Battery*>(); }
266 [[nodiscard]]
virtual Buffer<TemperatureSensor*> temperatureSensors()
const {
return Buffer<TemperatureSensor*>(); };
267 [[nodiscard]]
virtual OrientationSensor* orientationSensor()
const {
return nullptr; };
268 [[nodiscard]]
virtual PositionSensor* positionSensor()
const {
return nullptr; };
269 [[nodiscard]]
virtual Winch* deploymentWinch()
const {
return nullptr; }
270 [[nodiscard]]
virtual RotationBounds* rotationalBounds()
const {
return nullptr; };
271 [[nodiscard]]
virtual Light* light()
const {
return nullptr; }
272 [[nodiscard]]
virtual Light* redDot()
const {
return nullptr; }
273 [[nodiscard]]
virtual DistanceEncoder* distanceEncoder()
const {
return nullptr; }
274 [[nodiscard]]
virtual Connection* connection()
const {
return nullptr; }
275 [[nodiscard]]
virtual RangeSensor* rangeSensor()
const {
return m_range_sensor; };
277 [[nodiscard]]
virtual TimeSpan scanTime()
const;
278 [[nodiscard]]
virtual bool usingPrism()
const {
return false; };
279 [[nodiscard]]
virtual Log* maintenanceLog()
const {
return nullptr; };
280 [[nodiscard]]
virtual const ScanSetupSettings& scanSettings()
const {
return m_scan_settings; }
281 [[nodiscard]]
virtual Matrix<fltp08> initialScanTransform()
const;
282 virtual void updateModel();
283 virtual void clearScanStateRequests();
284 [[nodiscard]]
virtual bool isConnected()
const;
286 void scanStatusChangedSignal();
287 void scanStartedSignal();
288 void scanFinishedSignal(UUID
id);
289 void connectionChangedSignal(
bool is_connected);
291 virtual void setConnected(
bool is_connected);
292 virtual void createPrismModel();
293 virtual void createScannerModel();
294 [[nodiscard]]
virtual Bounds<2, Angle<fltp08>> scanBounds()
const = 0;
295 virtual void stopScan() = 0;
296 virtual void resumeScan() = 0;
297 virtual void pauseScan() = 0;
298 [[nodiscard]]
virtual FileRequest scanModelFile()
const;
299 [[nodiscard]]
virtual FileRequest prismModelFile()
const;
300 virtual void updateScanModel(
bool scan_ended,
bool force_calculate_mesh);
301 virtual void finishUpdatingScanModel();
302 virtual void calibrateScanModel();
303 virtual void createScanObject();
304 [[nodiscard]]
virtual Matrix<fltp08> laserTransform(
const Vector<3, Angle<fltp08>>& head_angle)
const = 0;
305 [[nodiscard]]
virtual Matrix<fltp08> scanTransform()
const {
return Matrix<fltp08>(1.0); }
307 Model m_camera_point_target;
308 Angle<sint04> m_anti_jitter_angle = Angle<sint04>(DEGREES, 0.3);
309 fltp08 m_anti_jitter_offset = 0.005;
310 Dictionary<String, std::function<void()>> m_camera_drape_functions;
311 DesignObjectLookup* m_manager;
313 ScannerState m_scanner_state;
314 ActiveScanStatus m_scan_status;
315 Vector<3, Motor*> m_head_motors;
316 RangeSensor* m_range_sensor;
318 UUID m_prism_model = Constant<UUID>::Invalid;
319 UUID m_camera = Constant<UUID>::Invalid;
321 ScanPointType m_scan_point_type;
323 Time m_scan_start_time;
324 Time m_start_pause_time;
325 TimeSpan m_pause_time;
328 ScanSetupSettings m_scan_settings;
329 bool m_is_scanning =
false;
330 bool m_is_paused =
false;
331 DynamicPointer<Scan> m_scan;
332 DynamicPointer<PointScannerOptions> m_options;
333 bool m_request_start_scan =
false;
334 bool m_request_pause_scan =
false;
335 bool m_request_stop_scan =
false;
336 bool m_request_disconnect =
false;
337 bool m_request_connect =
false;
338 bool m_file_loaded =
false;
339 bool m_mesh_with_head_angle =
false;
340 bool m_is_connected =
false;
A thread that executes a user-provided callback function concurrently.
A device which has an associated voltage or percent that changes.
A core object representing a user view as well as convenience functions for moving this view through ...
A standard interface for all types of connections that allow transmitting and receiving of data betwe...
A core class where all Design Objects including models, materials, and geometries are stored.
A root class which describes some physical object, such as a Motor, Sensor, or Connection.
A distance encoder is a device that measures distance by generating pulses in response to an object's...
A Device responsible for turning on and off a light source.
Serves as the primary program interface for processes to report issues and allows any number of LogSt...
A motor is a device which produces rotational spin.
Forward declaration for design object lookup service.
Forward declaration for distance encoder device.
A RangeSensor is a Device that determines the distance of a target at a certain orientation.
A Device responsible for determining the temperature of either the environment or a specific componen...
The primary namespace for the NDEVR SDK.
@ ROLL
Rotation about the forward axis (X).
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...
@ description
The description text of the object.
@ icon
Icon identifier for the object.
@ start_time
The time at which the effect begins.
@ e_normal
Normal map channel for per-pixel lighting.
A FileRequest bundles format data as well as a particular file.