global.hpp
1 #pragma once
2 
3 #include <array>
4 #include <functional>
5 #include <iterator>
6 #include <list>
7 #include <memory>
8 #include <mutex>
9 #include <vector>
10 
11 #include "namespace.hpp"
12 
13 #include "_cexports/c_core.h"
14 #include "_cexports/c_driver.h"
15 
16 #ifdef _DEBUG
17 # define CVB_FORCE_INLINE inline
18 #else // _DEBUG
19 # ifdef _MSC_VER
20 
21 # define CVB_FORCE_INLINE __forceinline
22 
23 # elif __GNUC__ && __cplusplus
24 
25 # define CVB_FORCE_INLINE inline __attribute__((always_inline))
26 
27 # else
28 
29 # endif
30 #endif // _DEBUG
31 
33 
48 namespace Cvb
49 {
50 
51 CVB_BEGIN_INLINE_NS
52 
53 class IArray;
54 class DataType;
55 class DeviceFactory;
56 class ImagePlane;
57 class LinearAccessData;
58 class Vpat;
59 
60 class Buffer;
63 
64 class BufferBase;
67 
68 class PFNCBuffer;
71 
72 class Plane;
75 
76 class PlaneEnumerator;
79 
80 class Image;
83 
84 class WrappedImage;
87 
91 
92 class Device;
95 
96 class Composite;
99 
100 class HandleOnly;
103 
104 class CancellationToken;
107 
111 
112 const double CVB_M_PI = 3.14159265358979323846;
113 
115 
116 template<class T>
118 
119 template<class T>
121 
123 enum class PixelDataType
124 {
130  Undefined,
134  UInt,
138  Int,
142  Float,
147 };
148 
150 enum class ColorModel
151 {
155  RGBGuess = CExports::CM_Guess_RGB,
159  MonoGuess = CExports::CM_Guess_Mono,
163  Unknown = CExports::CM_Unknown,
167  Mono = CExports::CM_Mono,
168 
169 #ifdef RGB
170 #undef RGB
171 #endif
172 
175  RGB = CExports::CM_RGB,
179  YUV = CExports::CM_YUV,
183  HSI = CExports::CM_HSI,
187  YCbCr = CExports::CM_YCbCr,
191  CieLUV = CExports::CM_LUV,
195  CieLab = CExports::CM_Lab,
199  HLS = CExports::CM_HLS,
203  YCC = CExports::CM_YCC,
207  HSV = CExports::CM_HSV,
211  CieXYZ = CExports::CM_XYZ
212 };
213 
215 
226 {
247 };
248 
251 {
255  Individual,
259  Identical
260 };
261 
264 {
273 
282 };
283 
285 enum class SubPixelMode
286 {
292  ParabolicFast = CExports::TSubPixelMode::SP_Parabolic_Fast,
293 
297  ParabolicAccurate = CExports::TSubPixelMode::SP_Parabolic_Accurate,
298 
302  Gaussian = CExports::TSubPixelMode::SP_Gauss
303 };
304 
306 
310 enum class Neighborhood
311 {
315  Use3x3 = 1,
316 
320  Use5x5 = 2,
321 
325  Use7x7 = 3,
326 
330  Use9x9 = 4
331 };
332 
334 enum class MappingOption
335 {
339  CopyPixels,
340 
346  LinkPixels
347 };
348 
350 enum class WaitStatus
351 {
353  Ok = CExports::CVDWS_Ok,
355  Timeout = CExports::CVDWS_Timeout,
357  Abort = CExports::CVDWS_Canceled
358 };
359 
361 
365 enum class PlaneRole
366 {
368  Undefined = CExports::CVCPR_Undefined,
369 
371  PixMono = CExports::CVCPR_PixMono,
373  PixRGB_R = CExports::CVCPR_PixRGB_R,
375  PixRGB_G = CExports::CVCPR_PixRGB_G,
377  PixRGB_B = CExports::CVCPR_PixRGB_B,
379  PixYUV_Y = CExports::CVCPR_PixYUV_Y,
381  PixYUV_U = CExports::CVCPR_PixYUV_U,
383  PixYUV_V = CExports::CVCPR_PixYUV_V,
385  PixHSV_H = CExports::CVCPR_PixHSV_H,
386  // Saturation channel value.
387  PixHSV_S = CExports::CVCPR_PixHSV_S,
389  PixHSV_V = CExports::CVCPR_PixHSV_V,
391  PixLAB_L = CExports::CVCPR_PixLAB_L,
393  PixLAB_A = CExports::CVCPR_PixLAB_A,
395  PixLAB_B = CExports::CVCPR_PixLAB_B,
397  PixConfidence = CExports::CVCPR_PixConfidence,
398 
400  CoordCartesian_X = CExports::CVCPR_CoordCartesian_X,
402  CoordCartesian_Y = CExports::CVCPR_CoordCartesian_Y,
404  CoordCartesian_Z = CExports::CVCPR_CoordCartesian_Z,
406  CoordCartesian_W = CExports::CVCPR_CoordCartesian_W,
408  CoordPolar_Rho = CExports::CVCPR_CoordPolar_Rho,
410  CoordPolar_Phi = CExports::CVCPR_CoordPolar_Phi,
412  CoordCylindrical_Rho = CExports::CVCPR_CoordCylindrical_Rho,
414  CoordCylindrical_Phi = CExports::CVCPR_CoordCylindrical_Phi,
416  CoordCylindrical_Z = CExports::CVCPR_CoordCylindrical_Z,
418  CoordSpherical_Rho = CExports::CVCPR_CoordSpherical_Rho,
420  CoordSpherical_Phi = CExports::CVCPR_CoordSpherical_Phi,
422  CoordSpherical_Theta = CExports::CVCPR_CoordSpherical_Theta,
424  Normal_X = CExports::CVCPR_Normal_X,
426  Normal_Y = CExports::CVCPR_Normal_Y,
428  Normal_Z = CExports::CVCPR_Normal_Z,
430  PointPlanarity = CExports::CVCPR_Point_Planarity,
432  PointVariation = CExports::CVCPR_Point_Variation,
434  PointSphericity = CExports::CVCPR_Point_Sphericity,
436  PointLinearity = CExports::CVCPR_Point_Linearity,
438  PointCurvature = CExports::CVCPR_Point_Curvature,
439 
441  Custom = CExports::CVCPR_Custom
442 };
443 
446 {
448  Horizontal = CExports::PM_Horizontal,
450  Vertical = CExports::PM_Vertical
451 };
452 
454 enum class ConnectionState
455 {
457  NotSupported,
459  Connected,
462 };
463 
464 enum class CompositePurpose
465 {
466  Custom = -1,
467  Image = 0,
468  ImageList,
469  MultiAoi,
470  RangeMap,
471  PointCloud,
472  ImageCube
473 };
474 
476 enum class ConversionMode
477 {
481  Automatic
482 };
483 
484 namespace Internal
485 {
486 
487 template <class T> class AsyncRef
488 {
489 public:
490  AsyncRef() = default;
491 
492  std::shared_ptr<T> AtomicGet(std::function<std::shared_ptr<T>()> create = nullptr)
493  {
494  std::unique_lock<std::mutex> guard(mutex_);
495  auto ref = weakRef_.lock();
496  if (!ref && create)
497  {
498  ref = create();
499  weakRef_ = ref;
500  }
501  return ref;
502  }
503 
504  void Reset() noexcept { weakRef_.reset(); }
505 
506 private:
507  std::mutex mutex_;
508 
509  std::weak_ptr<T> weakRef_;
510 };
511 
512 class HandlerCarrier
513 {
514 public:
515  HandlerCarrier() noexcept = default;
516  virtual ~HandlerCarrier() = default;
517 };
518 
519 typedef std::shared_ptr<HandlerCarrier> HandlerCarrierPtr;
520 typedef std::weak_ptr<HandlerCarrier> HandlerCarrierWPtr;
521 
522 class CarrierContainer;
523 
524 }
525 
527 
535 {
537  friend Internal::CarrierContainer;
539 
540 public:
542 
545  EventCookie() noexcept = default;
546 
548 
551  operator bool() const noexcept { return !handlerCarrier_.expired(); }
552 
553 private:
554  EventCookie(const Internal::HandlerCarrierPtr &handlerCarrier) { handlerCarrier_ = handlerCarrier; }
555 
556  Internal::HandlerCarrierWPtr handlerCarrier_;
557 };
558 
559 namespace Internal
560 {
561 
562 typedef void(REL_CB)(void *handle);
563 
564 }
565 
566 template <class T, Internal::REL_CB CB> class SharedHandleGuard;
567 
568 template <class T, Internal::REL_CB CB = nullptr> class HandleGuard
569 {
570 
571 public:
572  explicit HandleGuard(void *handle) noexcept : handle_(handle, CB)
573  {
574  static_assert(std::is_same<T, void>::value,
575  "CVB: HandleGuard need specialization, or type void with release callback!");
576  }
577 
578  HandleGuard(void *handle, std::function<void(void *)> deleter) noexcept : handle_(handle, deleter) {}
579 
580  void *Handle() const noexcept { return handle_.get(); }
581 
582  void Reset(void *handle = nullptr) noexcept { handle_.reset(handle); }
583 
584  void *Release() noexcept { return handle_.release(); }
585 
586 private:
587  std::unique_ptr<void, std::function<void(void *)>> handle_;
588 
589  friend class SharedHandleGuard<T, CB>;
590 };
591 
592 typedef HandleGuard<void, CVB_CALL_CAPI(ReleaseObjectVoid)> ReleaseObjectGuard;
593 
594 template <class T, Internal::REL_CB CB = nullptr> class SharedHandleGuard
595 {
596 public:
597  SharedHandleGuard(HandleGuard<T, CB> &&uniqueGuard) : shandle_(std::move(uniqueGuard.handle_)) {}
598 
599  SharedHandleGuard(const SharedHandleGuard &) = default;
600  SharedHandleGuard &operator=(const SharedHandleGuard &) = default;
601 
602  void *Handle() const noexcept { return shandle_.get(); }
603 
604 private:
605  std::shared_ptr<void> shandle_;
606 };
607 
608 typedef SharedHandleGuard<void, CVB_CALL_CAPI(ReleaseObjectVoid)> SharedReleaseObjectGuard;
609 
610 // forward declaration needed for gcc
611 namespace Utilities
612 {
613 
614 namespace SystemInfo
615 {
616 void ThrowLastError();
617 void ThrowLastError(int errorCode);
618 
619 }
620 
621 }
622 
623 namespace Internal
624 {
625 
626 template <class T> class CbCarrier : public HandlerCarrier
627 {
628 
629 public:
630  static std::shared_ptr<CbCarrier> Create(std::function<T> cb) { return std::make_shared<CbCarrier<T>>(cb); }
631 
632  CbCarrier(std::function<T> cb) noexcept : cb_(cb) {}
633 
634  std::function<T> CB() const noexcept { return cb_; }
635 
636 private:
637  std::function<T> cb_;
638 };
639 
640 class CarrierContainer
641 {
642 public:
643  CarrierContainer() noexcept {}
644 
645  CarrierContainer(CarrierContainer &&other) noexcept : carrierList_(std::move(other.carrierList_)) {}
646 
647  ~CarrierContainer() = default;
648 
649  EventCookie Register(const HandlerCarrierPtr &handlerBase) noexcept
650  {
651  std::unique_lock<std::mutex> guard(carrierListMutex_);
652  carrierList_.push_back(handlerBase);
653  return EventCookie(handlerBase);
654  }
655 
656  void Unregister(EventCookie eventCookie) noexcept
657  {
658  std::unique_lock<std::mutex> guard(carrierListMutex_);
659  auto handlerBase = eventCookie.handlerCarrier_.lock();
660  if (!handlerBase)
661  return;
662 
663  carrierList_.remove(handlerBase);
664  }
665 
666  template <class T, class... Args> void Call(Args &&... args) const
667  {
668  std::list<HandlerCarrierPtr> eventHolderList;
669  {
670  std::unique_lock<std::mutex> guard(carrierListMutex_);
671  eventHolderList.insert(eventHolderList.end(), carrierList_.begin(), carrierList_.end());
672  }
673  for (auto &holderBase : eventHolderList)
674  {
675  auto holder = std::dynamic_pointer_cast<CbCarrier<T>>(holderBase);
676  holder->CB()(std::forward<Args>(args)...);
677  }
678  }
679 
680 private:
681  CarrierContainer &operator=(CarrierContainer &&other) noexcept = delete;
682 
683  mutable std::mutex carrierListMutex_;
684  std::list<HandlerCarrierPtr> carrierList_;
685 };
686 
687 template <class OBJ, class RES, class... ARGS>
688 inline std::unique_ptr<OBJ> DoCallObjectOut(std::function<RES(void *&handle)> call, ARGS &&... args)
689 {
690  void *handle = nullptr;
691  auto code = CExports::MakeErrorCode(call(handle));
692  if (code < 0)
693  {
694  Utilities::SystemInfo::ThrowLastError(code);
695  }
696  return OBJ::FromHandle(HandleGuard<OBJ>(handle), std::forward<ARGS>(args)...);
697 }
698 
699 template <class OBJ, class... ARGS>
700 inline std::unique_ptr<OBJ> DoBoolCallObjectOut(std::function<CExports::cvbbool_t(void *&handle)> call, ARGS &&... args)
701 {
702  return DoCallObjectOut<OBJ, CExports::cvbbool_t, ARGS...>(call, std::forward<ARGS>(args)...);
703 }
704 
705 template <class OBJ, class... ARGS>
706 inline std::unique_ptr<OBJ> DoResCallObjectOut(std::function<CExports::cvbres_t(void *&handle)> call, ARGS &&... args)
707 {
708  return DoCallObjectOut<OBJ, CExports::cvbres_t, ARGS...>(call, std::forward<ARGS>(args)...);
709 }
710 
711 template <class OBJ> inline std::unique_ptr<OBJ> DoHandleCallObjectOut(void *result)
712 {
713  return DoCallObjectOut<OBJ, void *>([=](void *&handle) { return (handle = result); });
714 }
715 
716 template <class OBJ, class RES, class... ARGS>
717 inline std::shared_ptr<OBJ> DoCallShareOut(std::function<RES(void *&handle)> call, ARGS &&... args)
718 {
719  void *handle = nullptr;
720  auto code = CExports::MakeErrorCode(call(handle));
721  if (code < 0)
722  {
723  Utilities::SystemInfo::ThrowLastError(code);
724  }
725  return OBJ::template FromHandle<OBJ>(typename OBJ::GuardType(handle), std::forward<ARGS>(args)...);
726 }
727 
728 template <class OBJ, class... ARGS>
729 inline std::shared_ptr<OBJ> DoBoolCallShareOut(std::function<CExports::cvbbool_t(void *&handle)> call, ARGS &&... args)
730 {
731  return DoCallShareOut<OBJ, CExports::cvbbool_t, ARGS...>(call, std::forward<ARGS>(args)...);
732 }
733 
734 template <class OBJ, class... ARGS>
735 inline std::shared_ptr<OBJ> DoResCallShareOut(std::function<CExports::cvbres_t(void *&handle)> call, ARGS &&... args)
736 {
737  return DoCallShareOut<OBJ, CExports::cvbres_t, ARGS...>(call, std::forward<ARGS>(args)...);
738 }
739 
740 template <class T, class RES> inline T DoCallValueOut(std::function<RES(T &handle)> call)
741 {
742  T value;
743  auto code = CExports::MakeErrorCode(call(value));
744  if (code < 0)
745  {
746  Utilities::SystemInfo::ThrowLastError(code);
747  }
748  return value;
749 }
750 
751 template <class T> inline T DoBoolCallValueOut(std::function<CExports::cvbbool_t(T &handle)> call)
752 {
753  return DoCallValueOut<T, CExports::cvbbool_t>(call);
754 }
755 
756 template <class T> inline T DoResCallValueOut(std::function<CExports::cvbres_t(T &value)> call)
757 {
758  return DoCallValueOut<T, CExports::cvbres_t>(call);
759 }
760 
761 template <class RES> inline void DoCall(std::function<RES()> call)
762 {
763  auto code = CExports::MakeErrorCode(call());
764  if (code < 0)
765  Utilities::SystemInfo::ThrowLastError(code);
766 }
767 
768 inline void DoBoolCall(std::function<CExports::cvbbool_t()> call)
769 {
770  DoCall<CExports::cvbbool_t>(call);
771 }
772 
773 inline void DoResCall(std::function<CExports::cvbres_t()> call)
774 {
775  DoCall<CExports::cvbres_t>(call);
776 }
777 
778 class SmartBool final
779 {
780 public:
781  SmartBool() noexcept = default;
782  SmartBool(bool val) noexcept : cVal_(val ? 1 : 0) {}
783 
784 #if defined _WIN32
785  SmartBool(CExports::cvbbool_t val) noexcept : cVal_(val) {}
786 #endif
787 
788  operator bool() const noexcept { return ((cVal_) ? true : false); }
789 
790  CExports::cvbbool_t *Ptr() noexcept { return &cVal_; }
791 
792 private:
793  CExports::cvbbool_t cVal_ = 0;
794 };
795 
796 }
797 
798 template <class T>
799 using IsNumeric =
804 
805 template <class T> using EnableIfNumeric = std::enable_if<IsNumeric<T>::value>;
806 
807 template <class T> using EnableIfArithmetic = std::enable_if<std::is_arithmetic<T>::value>;
808 
809 template <class T, class... ARGS> struct AllOfType;
810 
811 template <class T, class ARG> struct AllOfType<T, ARG>
812 {
813  static constexpr bool Value =
816 };
817 
818 template <class T, class ARG, class... ARGS> struct AllOfType<T, ARG, ARGS...>
819 {
820  static constexpr bool Value =
823  AllOfType<T, ARGS...>::Value;
824 };
825 
826 template <typename RET, typename TYPE, class RANGE>
827 using TypedRange = std::enable_if<std::is_same<TYPE,
828  typename std::remove_const<typename std::remove_reference<decltype(
829  *std::begin(std::declval<RANGE &>()))>::type>::type>::value,
830  RET>;
831 
832 template <class RET, class TYPE, class... ARGS>
833 using VarArgRange = typename std::enable_if<AllOfType<TYPE, ARGS...>::Value, RET>;
834 
835 template <class TYPE, class RANGE> class RangeAdapter
836 {
837 public:
838  /* The constructor only stores the reference and compile-time-checks the value type.
839  * All operations are performed only when needed. */
840  RangeAdapter(const RANGE &range) : inputRef_(range)
841  {
842  static_assert(
844  typename std::remove_reference<decltype(*std::begin(std::declval<RANGE &>()))>::type>::type,
845  TYPE>::value,
846  "Unexpected range value type");
847  }
848 
849  /* Returns pointer to the range values in a contiguous memory block. */
850  TYPE *Data() const
851  {
852  /* TODO: should we actively check for empty container here? */
853  return const_cast<TYPE *>(Data(inputRef_.get()));
854  }
855 
856  /* Returns size of the range. */
857  std::size_t Size() const { return std::distance(std::begin(inputRef_.get()), std::end(inputRef_.get())); }
858 
859 private:
860  /* Actual input-range dependent workers for the contiguous data query. */
861  template <size_t N> const TYPE *Data(const TYPE (&carray)[N]) const { return carray; }
862 
863  template <size_t N> const TYPE *Data(const std::array<TYPE, N> &stdarray) const { return stdarray.data(); }
864 
865  const TYPE *Data(const std::vector<TYPE> &stdvec) const { return stdvec.data(); }
866 
867  template <class LIST> const TYPE *Data(const LIST &list) const
868  {
869  if (convertedRange_.empty())
870  {
871  convertedRange_.assign(std::begin(list), std::end(list));
872  }
873  return convertedRange_.data();
874  }
875 
876 private:
877  const std::reference_wrapper<const RANGE> inputRef_;
878  mutable std::vector<TYPE> convertedRange_;
879 };
880 
881 template <class TYPE, class RANGE>
882 RangeAdapter<TYPE, RANGE> MakeRangeAdapter(const RANGE &range, std::size_t minSize = 1)
883 {
884  RangeAdapter<TYPE, RANGE> rangeAdapter(range);
885  if (minSize != 0 && rangeAdapter.Size() < minSize)
886  throw std::runtime_error("insufficient number of input range values");
887  return rangeAdapter;
888 }
889 
890 template <class...>
891 struct DispatchableTypeList
892 {
893 };
894 
895 template <class DT, class... DTS>
896 struct DispatchableTypeList<DT, DTS...>
897 {
898  using DefaultType = DT;
899 };
900 
930 template <class PLANE_T>
931 struct PlaneTraits;
932 
933 CVB_END_INLINE_NS
934 
935 }
936 
PlaneNormalization
Plane handling for normalization.
Definition: global.hpp:250
Cartesian Y axis component.
Unknown/undefined value.
STL class.
Confidence(probability density / percentage) or consistency(Boolean) value.
WaitStatus
Status after waiting for an image to be returned.
Definition: global.hpp:350
The acquisition has been stopped asynchronously, there is no image buffer.
Base class of all buffers.
Definition: buffer_base.hpp:21
Blue channel value.
Planarity of points in cloud.
The Device object is currently disconnected from the remote hardware.
HandleOnly class is as it says a handle only.
Definition: handle_only.hpp:20
Point components of a dense point cloud.
Definition: dense_components_pointers_3d.hpp:14
Cartesian W axis component (homogeneous coordinates).
Cartesian Z axis component.
Everything is fine, a new image arrived.
Provides tokens and signals tokens cancellation.
Definition: cancellation_token_source.hpp:19
Connection state handling is not supported by the Device.
ConnectionState
Current connection state of the Device.
Definition: global.hpp:454
ConversionMode
Mode used by conversion to dense point cloud.
Definition: global.hpp:476
The Device object is currently connected to the remote hardware.
Neighborhood
Neighborhood to use in sub pixel calculation of local maxima.
Definition: global.hpp:310
Cylindrical radius component.
Mapped image of two merged source images.
Definition: panoramic_mapped_image.hpp:18
Spherical inclination/polar angle component.
Polar azimuth angle component.
Spherical azimuth angle component.
MappingOption
Mapping options when creating a (potentially) mapped image.
Definition: global.hpp:334
Value(luminance) channel value.
DeviceUpdateMode
Defines how to treat the optional device image, when the device itself is updated.
Definition: global.hpp:225
Variation of points in cloud.
Root namespace for the Image Manager interface.
Definition: version.hpp:11
A wrapped image wraps another pixel buffer without owning it.
Definition: decl_wrapped_image.hpp:28
The Common Vision Blox image.
Definition: decl_image.hpp:44
Red channel value.
Lazy enumeration of planes.
Definition: decl_plane_enumerator.hpp:27
Lightness channel value.
Spherical radius component.
Images are stitched vertically.
Green channel value.
CoordinateSystemType
Enumeration of the different available coordinate systems that an Area of interest may be defined in.
Definition: global.hpp:263
Green-red chrominance channel.
PanoramaDirection
Defines the direction of the panoramic image.
Definition: global.hpp:445
Hue channel value.
Cylindrical Z axis component.
Cylindrical azimuth angle component.
STL class.
Point components of the point cloud.
Definition: components_pointers_3d.hpp:18
T move(T... args)
Polar radius component.
PixelDataType
Defines the numeric data type of one pixel.
Definition: global.hpp:123
Images are stitched horizontally.
Blue chrominance channel.
Plane information container.
Definition: decl_plane.hpp:26
PlaneRole
A plane role describes the components of the plane. They can coarsely be separated in two sets.
Definition: global.hpp:365
ColorModel
Color model that this image is using.
Definition: global.hpp:150
STL class.
Same as PixMono, but to distinguish YUV model.
A token to enable cancellation on wait operations.
Definition: cancellation_token.hpp:19
STL class.
T ref(T... args)
SubPixelMode
Method for determining sub pixel accuracy when working with the FindLocalMaxima functions.
Definition: global.hpp:285
STL class.
Curvature of points in cloud.
Definition: global.hpp:931
A timeout occurred, no image buffer has been returned.
Component class is a container for CVB objects.
Definition: decl_composite.hpp:44
Cartesian X axis component.
PFNC buffer class implementing a pfnc buffer.
Definition: pfnc_buffer.hpp:15
Blue-yellow chrominance channel.
Linearity of points in cloud.
Red chrominance channel.
Point components of a sparse point cloud.
Definition: global.hpp:117
Generic CVB physical device.
Definition: decl_device.hpp:38
Sphericity of points in cloud.
Monochromatic, linear luminance value.
DataType
Describes the contents of a VariableNode.
Definition: opcua.hpp:186
Gets the value for an info key name.