diff --git a/SolARFramework.pro b/SolARFramework.pro index 33c9b433..51cf1ea9 100755 --- a/SolARFramework.pro +++ b/SolARFramework.pro @@ -42,9 +42,11 @@ DEFINES += "_BCOM_SHARED=__declspec(dllexport)" include (SolARFramework.pri) +DEFINES += XPCF_DISABLE_ATTRIBUTES + unix { # Avoids adding install steps manually. To be commented to have a better control over them. - QMAKE_POST_LINK += "make install" + QMAKE_POST_LINK += "$(MAKE) install" } linux { diff --git a/interfaces/api/display/I2DOverlay.h b/interfaces/api/display/I2DOverlay.h index e2820e4a..c7b20aae 100644 --- a/interfaces/api/display/I2DOverlay.h +++ b/interfaces/api/display/I2DOverlay.h @@ -36,7 +36,7 @@ namespace display { * This class provides drawing methods to overlay 2D debug informations on top of an image. */ -class [[xpcf::clientUUID("f7d538cd-1d6f-4daa-8701-3e31357c213e")]] [[xpcf::serverUUID("ad47d50c-83d6-4b63-af31-8cf3642addd0")]] I2DOverlay : +class XPCF_CLIENTUUID("f7d538cd-1d6f-4daa-8701-3e31357c213e") XPCF_SERVERUUID("ad47d50c-83d6-4b63-af31-8cf3642addd0") I2DOverlay : virtual public org::bcom::xpcf::IComponentIntrospect { public: /// @brief I2DOverlay default constructor diff --git a/interfaces/api/display/I3DOverlay.h b/interfaces/api/display/I3DOverlay.h index 5ed9aba5..506b4a2e 100644 --- a/interfaces/api/display/I3DOverlay.h +++ b/interfaces/api/display/I3DOverlay.h @@ -34,7 +34,7 @@ namespace display { * * This class provides drawing method to overlay 3D debug informations on top of an image. */ -class [[xpcf::clientUUID("ce48f688-bb48-4d61-800c-e504c0d060a8")]] [[xpcf::serverUUID("cb391967-f407-4a67-b092-26d44de001ce")]] I3DOverlay : +class XPCF_CLIENTUUID("ce48f688-bb48-4d61-800c-e504c0d060a8") XPCF_SERVERUUID("cb391967-f407-4a67-b092-26d44de001ce") I3DOverlay : virtual public org::bcom::xpcf::IComponentIntrospect { public: /// @brief I3DOverlay default constructor diff --git a/interfaces/api/display/I3DPointsViewer.h b/interfaces/api/display/I3DPointsViewer.h index 100f3876..e782ba13 100644 --- a/interfaces/api/display/I3DPointsViewer.h +++ b/interfaces/api/display/I3DPointsViewer.h @@ -33,7 +33,7 @@ namespace display { * * This class provides a viewer to display points cloud in a window. */ -class [[xpcf::clientUUID("423cd9a6-f93a-4e1b-88f0-0762c1db5db3")]] [[xpcf::serverUUID("15e7a40b-9269-40a1-b95d-7139cff7ee4c")]] I3DPointsViewer : +class XPCF_CLIENTUUID("423cd9a6-f93a-4e1b-88f0-0762c1db5db3") XPCF_SERVERUUID("15e7a40b-9269-40a1-b95d-7139cff7ee4c") I3DPointsViewer : virtual public org::bcom::xpcf::IComponentIntrospect { public: /// @brief I3DPointsViewer default constructor diff --git a/interfaces/api/display/IImageViewer.h b/interfaces/api/display/IImageViewer.h index d3aa8fa9..1413a8c5 100644 --- a/interfaces/api/display/IImageViewer.h +++ b/interfaces/api/display/IImageViewer.h @@ -32,7 +32,7 @@ namespace display { * This class provides a viewer to display an image in a window. */ -class [[xpcf::clientUUID("a580d26e-331d-42d4-8bfe-f19913ba97fb")]] [[xpcf::serverUUID("b99d8c4e-10ef-4d7a-ba7c-dfa114cf1620")]] IImageViewer : +class XPCF_CLIENTUUID("a580d26e-331d-42d4-8bfe-f19913ba97fb") XPCF_SERVERUUID("b99d8c4e-10ef-4d7a-ba7c-dfa114cf1620") IImageViewer : virtual public org::bcom::xpcf::IComponentIntrospect { public: virtual ~IImageViewer() = default; diff --git a/interfaces/api/display/IMaskOverlay.h b/interfaces/api/display/IMaskOverlay.h index d33d1dec..3f3f180f 100644 --- a/interfaces/api/display/IMaskOverlay.h +++ b/interfaces/api/display/IMaskOverlay.h @@ -32,7 +32,7 @@ namespace display { * UUID: 35a2454a-cb09-44ac-b2ce-0b0732175f94 */ -class [[xpcf::clientUUID("10d2d826-714e-4eb9-91d4-9c577585ddfe")]] [[xpcf::serverUUID("86974141-74a8-40a2-8150-c20eda855ed4")]] IMaskOverlay : +class XPCF_CLIENTUUID("10d2d826-714e-4eb9-91d4-9c577585ddfe") XPCF_SERVERUUID("86974141-74a8-40a2-8150-c20eda855ed4") IMaskOverlay : virtual public org::bcom::xpcf::IComponentIntrospect { public: /// @brief IMaskOverlay default constructor diff --git a/interfaces/api/display/IMatchesOverlay.h b/interfaces/api/display/IMatchesOverlay.h index 235c119b..39741417 100644 --- a/interfaces/api/display/IMatchesOverlay.h +++ b/interfaces/api/display/IMatchesOverlay.h @@ -35,7 +35,7 @@ namespace display { * * This class provides drawing method to overlay matches between two images. */ -class [[xpcf::clientUUID("a35aa6c7-ce39-4158-866d-5b0210267c12")]] [[xpcf::serverUUID("ef9096d0-c4ec-430d-8424-993b9010e3e3")]] IMatchesOverlay : +class XPCF_CLIENTUUID("a35aa6c7-ce39-4158-866d-5b0210267c12") XPCF_SERVERUUID("ef9096d0-c4ec-430d-8424-993b9010e3e3") IMatchesOverlay : virtual public org::bcom::xpcf::IComponentIntrospect { public: /// @brief IMatchesOverlay default constructor diff --git a/interfaces/api/features/I2DTrackablesDetector.h b/interfaces/api/features/I2DTrackablesDetector.h index d00e48f8..c71a28c3 100644 --- a/interfaces/api/features/I2DTrackablesDetector.h +++ b/interfaces/api/features/I2DTrackablesDetector.h @@ -32,7 +32,7 @@ namespace features { * @brief Detect a set of given 2D trackables in an image. * UUID: 607d0b0d-766d-4ff2-9b72-45c555f9726f */ -class [[xpcf::clientUUID("b62759a5-069a-40b0-846e-71f6adc9cb5e")]] [[xpcf::serverUUID("b73bdd5a-aecb-4e63-b40f-cd05fa7b8490")]] I2DTrackablesDetector : +class XPCF_CLIENTUUID("b62759a5-069a-40b0-846e-71f6adc9cb5e") XPCF_SERVERUUID("b73bdd5a-aecb-4e63-b40f-cd05fa7b8490") I2DTrackablesDetector : virtual public org::bcom::xpcf::IComponentIntrospect { public: ///@brief I2DTrackablesDetector default constructor. diff --git a/interfaces/api/features/IContoursExtractor.h b/interfaces/api/features/IContoursExtractor.h index b3bbd5c1..8fa429db 100644 --- a/interfaces/api/features/IContoursExtractor.h +++ b/interfaces/api/features/IContoursExtractor.h @@ -34,7 +34,7 @@ namespace features { */ -class [[xpcf::clientUUID("892788ad-8366-4d79-aec8-92aa4ed34665")]] [[xpcf::serverUUID("a2e6ed26-7795-407b-b7e6-e04140c8ab80")]] IContoursExtractor : +class XPCF_CLIENTUUID("892788ad-8366-4d79-aec8-92aa4ed34665") XPCF_SERVERUUID("a2e6ed26-7795-407b-b7e6-e04140c8ab80") IContoursExtractor : virtual public org::bcom::xpcf::IComponentIntrospect { public: /// @brief IContoursExtractor default constructor diff --git a/interfaces/api/features/IContoursFilter.h b/interfaces/api/features/IContoursFilter.h index f0d0fceb..560d6f54 100644 --- a/interfaces/api/features/IContoursFilter.h +++ b/interfaces/api/features/IContoursFilter.h @@ -34,7 +34,7 @@ namespace features { * This class provides a filtering method to prune a set of contours. */ -class [[xpcf::clientUUID("a8cad1a4-be07-43df-90f3-4bf7d7481528")]] [[xpcf::serverUUID("571317b1-4fe5-44cc-bf86-4c4c079150c3")]] IContoursFilter : +class XPCF_CLIENTUUID("a8cad1a4-be07-43df-90f3-4bf7d7481528") XPCF_SERVERUUID("571317b1-4fe5-44cc-bf86-4c4c079150c3") IContoursFilter : virtual public org::bcom::xpcf::IComponentIntrospect { public: /// @brief IContoursFilter default constructor diff --git a/interfaces/api/features/ICornerRefinement.h b/interfaces/api/features/ICornerRefinement.h index 342732a0..b5c80b52 100644 --- a/interfaces/api/features/ICornerRefinement.h +++ b/interfaces/api/features/ICornerRefinement.h @@ -42,7 +42,7 @@ namespace features { * * This class provides a method to refine the corner locations. */ -class [[xpcf::clientUUID("b33148d7-0366-4167-a641-1efb43869715")]] [[xpcf::serverUUID("c730d426-c7ee-41ec-acae-31bc0a98329c")]] ICornerRefinement : +class XPCF_CLIENTUUID("b33148d7-0366-4167-a641-1efb43869715") XPCF_SERVERUUID("c730d426-c7ee-41ec-acae-31bc0a98329c") ICornerRefinement : virtual public org::bcom::xpcf::IComponentIntrospect { public: diff --git a/interfaces/api/features/IDescriptorMatcher.h b/interfaces/api/features/IDescriptorMatcher.h index 31017514..72abc8ff 100644 --- a/interfaces/api/features/IDescriptorMatcher.h +++ b/interfaces/api/features/IDescriptorMatcher.h @@ -40,7 +40,7 @@ namespace features { * UUID: dda38a40-c50a-4e7d-8433-0f04c7c98518 * Just implement the first interface, the second interface is implemented in ADescriptorMatcher. */ -class [[xpcf::clientUUID("97adde0e-bb1f-45ee-b9de-3ce6b1275550")]] [[xpcf::serverUUID("b273541a-ec8c-4614-9b3e-7b11d27ac9f7")]] IDescriptorMatcher : +class XPCF_CLIENTUUID("97adde0e-bb1f-45ee-b9de-3ce6b1275550") XPCF_SERVERUUID("b273541a-ec8c-4614-9b3e-7b11d27ac9f7") IDescriptorMatcher : virtual public org::bcom::xpcf::IComponentIntrospect { public: /// @brief IDescriptorMatcher default constructor diff --git a/interfaces/api/features/IDescriptorMatcherGeometric.h b/interfaces/api/features/IDescriptorMatcherGeometric.h index 9e739cec..aaa9efaa 100644 --- a/interfaces/api/features/IDescriptorMatcherGeometric.h +++ b/interfaces/api/features/IDescriptorMatcherGeometric.h @@ -40,7 +40,7 @@ namespace features { * UUID: 2ed445a6-32f3-44a1-9dc5-3b0cfec778db * Just implement the first interface, the second interface is implemented in ADescriptorMatcherGeometric. */ -class [[xpcf::clientUUID("1bd62a3f-3376-45c3-a980-94d042ae509f")]] [[xpcf::serverUUID("75930efc-a96e-4d07-86b0-2ab2d9ea0102")]] IDescriptorMatcherGeometric : +class XPCF_CLIENTUUID("1bd62a3f-3376-45c3-a980-94d042ae509f") XPCF_SERVERUUID("75930efc-a96e-4d07-86b0-2ab2d9ea0102") IDescriptorMatcherGeometric : virtual public org::bcom::xpcf::IComponentIntrospect { public: /// @brief IDescriptorMatcherGeometric default constructor diff --git a/interfaces/api/features/IDescriptorMatcherRegion.h b/interfaces/api/features/IDescriptorMatcherRegion.h index dfd487e8..25c8a486 100644 --- a/interfaces/api/features/IDescriptorMatcherRegion.h +++ b/interfaces/api/features/IDescriptorMatcherRegion.h @@ -40,7 +40,7 @@ namespace features { * UUID: bdef063d-96de-4425-83c5-fec7b7e448c8 * Just implement the first interface, the second and third interface are implemented in ADescriptorMatcherRegion. */ -class [[xpcf::clientUUID("92474130-2e1c-471c-aafe-c84c5144552f")]] [[xpcf::serverUUID("b4ca2b4f-cbcc-4688-be15-301b3d4b081c")]] IDescriptorMatcherRegion : +class XPCF_CLIENTUUID("92474130-2e1c-471c-aafe-c84c5144552f") XPCF_SERVERUUID("b4ca2b4f-cbcc-4688-be15-301b3d4b081c") IDescriptorMatcherRegion : virtual public org::bcom::xpcf::IComponentIntrospect { public: /// @brief IDescriptorMatcherRegion default constructor diff --git a/interfaces/api/features/IDescriptorMatcherStereo.h b/interfaces/api/features/IDescriptorMatcherStereo.h index c04b4769..1c2bf6c1 100644 --- a/interfaces/api/features/IDescriptorMatcherStereo.h +++ b/interfaces/api/features/IDescriptorMatcherStereo.h @@ -35,7 +35,7 @@ namespace features { * UUID: 272f1ef0-c269-4631-b75c-fc7316d10915 * Just implement the first interface, the second interface is implemented in ADescriptorMatcherStereo. */ -class [[xpcf::clientUUID("06bc0b35-6240-4bb9-ae8a-1de2c5f77a13")]] [[xpcf::serverUUID("9f72e88e-ca7a-4ac9-af81-cf08382dda03")]] IDescriptorMatcherStereo : +class XPCF_CLIENTUUID("06bc0b35-6240-4bb9-ae8a-1de2c5f77a13") XPCF_SERVERUUID("9f72e88e-ca7a-4ac9-af81-cf08382dda03") IDescriptorMatcherStereo : virtual public org::bcom::xpcf::IComponentIntrospect { public: /// @brief IDescriptorMatcherStereo constructor diff --git a/interfaces/api/features/IDescriptorsExtractor.h b/interfaces/api/features/IDescriptorsExtractor.h index 63cf735b..b4a89cb0 100644 --- a/interfaces/api/features/IDescriptorsExtractor.h +++ b/interfaces/api/features/IDescriptorsExtractor.h @@ -46,7 +46,7 @@ namespace features { * * This class provides a method to extract descriptors from a set of keypoints */ - class [[xpcf::clientUUID("79b1a2c4-639c-42ef-832f-130cf6131271")]] [[xpcf::serverUUID("a5bcfadd-4a12-45b3-a90f-0f1a82d51d12")]] IDescriptorsExtractor : + class XPCF_CLIENTUUID("79b1a2c4-639c-42ef-832f-130cf6131271") XPCF_SERVERUUID("a5bcfadd-4a12-45b3-a90f-0f1a82d51d12") IDescriptorsExtractor : virtual public org::bcom::xpcf::IComponentIntrospect { public: /// diff --git a/interfaces/api/features/IDescriptorsExtractorFromImage.h b/interfaces/api/features/IDescriptorsExtractorFromImage.h index 89ac58a0..e5db585e 100644 --- a/interfaces/api/features/IDescriptorsExtractorFromImage.h +++ b/interfaces/api/features/IDescriptorsExtractorFromImage.h @@ -44,7 +44,7 @@ namespace features { * * This class provides a method to extract descriptors directly from an image */ -class [[xpcf::clientUUID("6ed44a98-6743-414e-84de-970fab9b3507")]] [[xpcf::serverUUID("1df6caec-4032-48ae-9a46-72e40aadf0a5")]] IDescriptorsExtractorFromImage : +class XPCF_CLIENTUUID("6ed44a98-6743-414e-84de-970fab9b3507") XPCF_SERVERUUID("1df6caec-4032-48ae-9a46-72e40aadf0a5") IDescriptorsExtractorFromImage : virtual public org::bcom::xpcf::IComponentIntrospect { public: /// @brief IDescriptorsExtractorFromImage default constructor diff --git a/interfaces/api/features/IDescriptorsExtractorSBPattern.h b/interfaces/api/features/IDescriptorsExtractorSBPattern.h index f4edad09..5ab8481d 100644 --- a/interfaces/api/features/IDescriptorsExtractorSBPattern.h +++ b/interfaces/api/features/IDescriptorsExtractorSBPattern.h @@ -34,7 +34,7 @@ namespace features { * * This class provides a method to extract descriptors of a squared binary pattern by simply concatenating pattern rows in a single vector. */ -class [[xpcf::clientUUID("c2a230ae-6fb0-4e30-b06c-05c29c6feb9b")]] [[xpcf::serverUUID("b79db157-da75-4e58-be04-f82a7c54dc7c")]] IDescriptorsExtractorSBPattern : +class XPCF_CLIENTUUID("c2a230ae-6fb0-4e30-b06c-05c29c6feb9b") XPCF_SERVERUUID("b79db157-da75-4e58-be04-f82a7c54dc7c") IDescriptorsExtractorSBPattern : virtual public org::bcom::xpcf::IComponentIntrospect { public: diff --git a/interfaces/api/features/IFeatureWithDepthFromStereo.h b/interfaces/api/features/IFeatureWithDepthFromStereo.h index 4fcff636..7453e94c 100644 --- a/interfaces/api/features/IFeatureWithDepthFromStereo.h +++ b/interfaces/api/features/IFeatureWithDepthFromStereo.h @@ -31,7 +31,7 @@ namespace features { * @brief Perform feature extraction and keypoint depth estimation from each stereo images. * UUID: 10853f36-c0c0-4afb-81b8-0b1a06ca4e71 */ -class [[xpcf::clientUUID("23c6b83f-d6a2-415b-a7ba-21556d28cad9")]] [[xpcf::serverUUID("a5a81922-7bac-44b1-a561-9c7b83a07589")]] IFeatureWithDepthFromStereo : +class XPCF_CLIENTUUID("23c6b83f-d6a2-415b-a7ba-21556d28cad9") XPCF_SERVERUUID("a5a81922-7bac-44b1-a561-9c7b83a07589") IFeatureWithDepthFromStereo : virtual public org::bcom::xpcf::IComponentIntrospect { public: /// @brief IFeatureWithDepthFromStereo constructor diff --git a/interfaces/api/features/IImageMatcher.h b/interfaces/api/features/IImageMatcher.h index 5259e4df..abbc3ba7 100644 --- a/interfaces/api/features/IImageMatcher.h +++ b/interfaces/api/features/IImageMatcher.h @@ -39,7 +39,7 @@ namespace features { */ -class [[xpcf::clientUUID("0fcb5bf1-7251-4c7d-a3cc-3da7b4c306f4")]] [[xpcf::serverUUID("6b8f3e75-1745-45aa-a3bc-ac9c76c4d7db")]] IImageMatcher: +class XPCF_CLIENTUUID("0fcb5bf1-7251-4c7d-a3cc-3da7b4c306f4") XPCF_SERVERUUID("6b8f3e75-1745-45aa-a3bc-ac9c76c4d7db") IImageMatcher: virtual public org::bcom::xpcf::IComponentIntrospect { public: diff --git a/interfaces/api/features/IKeypointDetector.h b/interfaces/api/features/IKeypointDetector.h index 6e85f9a0..eaabdae3 100644 --- a/interfaces/api/features/IKeypointDetector.h +++ b/interfaces/api/features/IKeypointDetector.h @@ -46,7 +46,7 @@ namespace features { * * This class provides a method to detect the keypoint from an image using different kind of method (SURF, ORB, SIFT, etc.). */ -class [[xpcf::clientUUID("e16c54b9-bec7-46f3-9118-e884f60792e8")]] [[xpcf::serverUUID("7094b3a7-e257-46bf-84c5-c5e5ce3b8d39")]] IKeypointDetector : +class XPCF_CLIENTUUID("e16c54b9-bec7-46f3-9118-e884f60792e8") XPCF_SERVERUUID("7094b3a7-e257-46bf-84c5-c5e5ce3b8d39") IKeypointDetector : virtual public org::bcom::xpcf::IComponentIntrospect { public: diff --git a/interfaces/api/features/IKeypointDetectorRegion.h b/interfaces/api/features/IKeypointDetectorRegion.h index edc1e11d..311499d0 100644 --- a/interfaces/api/features/IKeypointDetectorRegion.h +++ b/interfaces/api/features/IKeypointDetectorRegion.h @@ -45,7 +45,7 @@ namespace features { * * This class provides a method to detect the keypoint from an given region of an image using different kind of method (SURF, ORB, SIFT, etc.). */ -class [[xpcf::clientUUID("984ae965-bc03-42d4-8acd-7dcb4e9ac4aa")]] [[xpcf::serverUUID("ecce7865-2ae3-4b51-b267-28067beb742c")]] IKeypointDetectorRegion : +class XPCF_CLIENTUUID("984ae965-bc03-42d4-8acd-7dcb4e9ac4aa") XPCF_SERVERUUID("ecce7865-2ae3-4b51-b267-28067beb742c") IKeypointDetectorRegion : virtual public org::bcom::xpcf::IComponentIntrospect { public: diff --git a/interfaces/api/features/IKeypointsReIndexer.h b/interfaces/api/features/IKeypointsReIndexer.h index ae3549af..53c3ce3e 100644 --- a/interfaces/api/features/IKeypointsReIndexer.h +++ b/interfaces/api/features/IKeypointsReIndexer.h @@ -33,7 +33,7 @@ namespace features { * @brief Reorganizes the keypoints detected from two images that match together in two vector of points where the nth point of the first vector matches with the nth point of the second vector. * UUID: 920e64a2-df17-11e7-80c1-9a214cf093ae */ -class [[xpcf::clientUUID("681727ef-5122-4b21-8cd0-e56314c215bc")]] [[xpcf::serverUUID("0305c89a-f5f2-46ce-a3a3-c795179f8e8c")]] IKeypointsReIndexer : +class XPCF_CLIENTUUID("681727ef-5122-4b21-8cd0-e56314c215bc") XPCF_SERVERUUID("0305c89a-f5f2-46ce-a3a3-c795179f8e8c") IKeypointsReIndexer : virtual public org::bcom::xpcf::IComponentIntrospect { public: /// @brief IKeypointsReIndexer default constructor diff --git a/interfaces/api/features/IMatchesFilter.h b/interfaces/api/features/IMatchesFilter.h index bbb903ae..fb21bb1c 100644 --- a/interfaces/api/features/IMatchesFilter.h +++ b/interfaces/api/features/IMatchesFilter.h @@ -16,7 +16,7 @@ namespace features { * @brief Filters a set of matches. * UUID: e0d6cc82-6af2-493d-901a-2384fca0b16f */ - class [[xpcf::clientUUID("72253404-a06f-4b3f-996e-b17d5aaba9b4")]] [[xpcf::serverUUID("04f5af9a-c533-4776-ad25-f7f0f80315ee")]]IMatchesFilter : + class XPCF_CLIENTUUID("72253404-a06f-4b3f-996e-b17d5aaba9b4") XPCF_SERVERUUID("04f5af9a-c533-4776-ad25-f7f0f80315ee")IMatchesFilter : virtual public org::bcom::xpcf::IComponentIntrospect { public: ///@brief IMatchesFilter default constructor. diff --git a/interfaces/api/features/ISBPatternReIndexer.h b/interfaces/api/features/ISBPatternReIndexer.h index fc41f3c3..d7acb788 100644 --- a/interfaces/api/features/ISBPatternReIndexer.h +++ b/interfaces/api/features/ISBPatternReIndexer.h @@ -32,7 +32,7 @@ namespace features { * @brief Gives both the 4 corners of a pattern in its reference coordinate system (pixels, cells, etc.) and the 4 corners in pixels of this pattern in the current image. * UUID: 79c5b810-d557-11e7-9296-cec278b6b50a */ -class [[xpcf::clientUUID("f6633107-382c-44d1-bbee-e3223946f608")]] [[xpcf::serverUUID("2c59c1e6-c757-4147-9c97-12cd7878f88d")]] ISBPatternReIndexer : +class XPCF_CLIENTUUID("f6633107-382c-44d1-bbee-e3223946f608") XPCF_SERVERUUID("2c59c1e6-c757-4147-9c97-12cd7878f88d") ISBPatternReIndexer : virtual public org::bcom::xpcf::IComponentIntrospect { public: /// @brief ISBPatternReIndexer default constructor diff --git a/interfaces/api/fusion/IVisualInertialFusion.h b/interfaces/api/fusion/IVisualInertialFusion.h index b35e90ac..66c37881 100644 --- a/interfaces/api/fusion/IVisualInertialFusion.h +++ b/interfaces/api/fusion/IVisualInertialFusion.h @@ -51,7 +51,7 @@ struct VisionData { * * This class provides a fusion method to process inputs from both visual and inertial sensors. */ -class [[xpcf::clientUUID("71f122b4-e42a-498e-8792-4a4807f7d61d")]] [[xpcf::serverUUID("10fa56bd-9679-47c3-86d8-2956edc18783")]] IVisualInertialFusion : +class XPCF_CLIENTUUID("71f122b4-e42a-498e-8792-4a4807f7d61d") XPCF_SERVERUUID("10fa56bd-9679-47c3-86d8-2956edc18783") IVisualInertialFusion : virtual public org::bcom::xpcf::IComponentIntrospect { public: /// @brief IVisualInertialFusion default constructor diff --git a/interfaces/api/geom/I2DPointsRectification.h b/interfaces/api/geom/I2DPointsRectification.h index e06fd85b..a23be640 100644 --- a/interfaces/api/geom/I2DPointsRectification.h +++ b/interfaces/api/geom/I2DPointsRectification.h @@ -32,7 +32,7 @@ namespace geom { * UUID: 188e9e9c-6d73-4495-9d9f-3bc5d35c4b43 * Just implement the first interface, the second interface is implemented in A2DPointsRectification. */ -class [[xpcf::clientUUID("7ec39cd6-c0e1-4b4d-a064-e42e56fc258b")]] [[xpcf::serverUUID("e02ef0d2-b3b1-4a2d-b088-f236b9447fed")]] I2DPointsRectification : +class XPCF_CLIENTUUID("7ec39cd6-c0e1-4b4d-a064-e42e56fc258b") XPCF_SERVERUUID("e02ef0d2-b3b1-4a2d-b088-f236b9447fed") I2DPointsRectification : virtual public org::bcom::xpcf::IComponentIntrospect { public: /// @brief I2DPointsRectification constructor diff --git a/interfaces/api/geom/I2DTransform.h b/interfaces/api/geom/I2DTransform.h index 3c773f08..83af78f0 100644 --- a/interfaces/api/geom/I2DTransform.h +++ b/interfaces/api/geom/I2DTransform.h @@ -32,7 +32,7 @@ namespace geom { * UUID: dbf5a8a1-cbcb-4a95-8dfd-4d9d5877e56f */ -class [[xpcf::clientUUID("125ebd15-d7b2-4f20-98a9-572a48d477bf")]] [[xpcf::serverUUID("e59ed354-1ddc-4f89-b445-31001e0acc67")]] I2DTransform : +class XPCF_CLIENTUUID("125ebd15-d7b2-4f20-98a9-572a48d477bf") XPCF_SERVERUUID("e59ed354-1ddc-4f89-b445-31001e0acc67") I2DTransform : virtual public org::bcom::xpcf::IComponentIntrospect { public: /// @brief I2DTransform default constructor diff --git a/interfaces/api/geom/I3DTransform.h b/interfaces/api/geom/I3DTransform.h index d38f8f0f..809d6cd2 100644 --- a/interfaces/api/geom/I3DTransform.h +++ b/interfaces/api/geom/I3DTransform.h @@ -35,7 +35,7 @@ namespace geom { * UUID: 9c1052b2-46c0-467b-8363-36f19b6b445f */ -class [[xpcf::clientUUID("600dd260-12ff-4fa3-877a-0db9d490e20e")]] [[xpcf::serverUUID("a8c4d66c-b112-49a2-9eae-d9e1fd0e34b5")]] I3DTransform : +class XPCF_CLIENTUUID("600dd260-12ff-4fa3-877a-0db9d490e20e") XPCF_SERVERUUID("a8c4d66c-b112-49a2-9eae-d9e1fd0e34b5") I3DTransform : virtual public org::bcom::xpcf::IComponentIntrospect { public: /// @brief I3DTransform default constructor diff --git a/interfaces/api/geom/IDepthEstimation.h b/interfaces/api/geom/IDepthEstimation.h index 7a6ff0fa..d8a6f166 100644 --- a/interfaces/api/geom/IDepthEstimation.h +++ b/interfaces/api/geom/IDepthEstimation.h @@ -31,7 +31,7 @@ namespace geom { * @brief Depth estimation based on disparity of matched features. * UUID: 0d3c4b5d-bbb2-4adc-80b0-b7e8720a704d */ -class [[xpcf::clientUUID("a0d958fd-53ed-490b-aec4-2a5a93a60d98")]] [[xpcf::serverUUID("d47a2503-e1c6-4db2-9bff-52a3259bcbe1")]] IDepthEstimation : +class XPCF_CLIENTUUID("a0d958fd-53ed-490b-aec4-2a5a93a60d98") XPCF_SERVERUUID("d47a2503-e1c6-4db2-9bff-52a3259bcbe1") IDepthEstimation : virtual public org::bcom::xpcf::IComponentIntrospect { public: /// @brief IDepthEstimation constructor diff --git a/interfaces/api/geom/IImage2WorldMapper.h b/interfaces/api/geom/IImage2WorldMapper.h index 82b46aed..1b3f4e3e 100644 --- a/interfaces/api/geom/IImage2WorldMapper.h +++ b/interfaces/api/geom/IImage2WorldMapper.h @@ -32,7 +32,7 @@ namespace geom { * UUID: 67bcd080-258d-4b16-b693-cd30c013eb05 */ -class [[xpcf::clientUUID("79e05ea9-ff48-45fd-aa04-bad8441bf8b0")]] [[xpcf::serverUUID("2dcd37ad-0c08-4793-b249-b0dd56b5bf12")]] IImage2WorldMapper : +class XPCF_CLIENTUUID("79e05ea9-ff48-45fd-aa04-bad8441bf8b0") XPCF_SERVERUUID("2dcd37ad-0c08-4793-b249-b0dd56b5bf12") IImage2WorldMapper : virtual public org::bcom::xpcf::IComponentIntrospect { public: /// @brief IImage2WorldMapper default constructor diff --git a/interfaces/api/geom/IProject.h b/interfaces/api/geom/IProject.h index ae8efc3f..703d2240 100644 --- a/interfaces/api/geom/IProject.h +++ b/interfaces/api/geom/IProject.h @@ -33,7 +33,7 @@ namespace geom { * UUID: b485f37d-a8ea-49f6-b361-f2b30777d9ba */ -class [[xpcf::clientUUID("64351b8a-7801-4ca9-841f-a4254506abc3")]] [[xpcf::serverUUID("8edec0aa-8547-49b0-a1a5-0eb148e44386")]] IProject : +class XPCF_CLIENTUUID("64351b8a-7801-4ca9-841f-a4254506abc3") XPCF_SERVERUUID("8edec0aa-8547-49b0-a1a5-0eb148e44386") IProject : virtual public org::bcom::xpcf::IComponentIntrospect { public: /// @brief IProjection default constructor diff --git a/interfaces/api/geom/IReprojectionStereo.h b/interfaces/api/geom/IReprojectionStereo.h index 53831e49..6f08897c 100644 --- a/interfaces/api/geom/IReprojectionStereo.h +++ b/interfaces/api/geom/IReprojectionStereo.h @@ -33,7 +33,7 @@ namespace geom { * UUID: 166a0aad-8c0a-4cdc-9edf-41ff9e514212 * Just implement the first and second interface, the third interface is implemented in AReprojectionStereo. */ -class [[xpcf::clientUUID("6bb5443e-ffa3-47f1-9276-54577fcd5368")]] [[xpcf::serverUUID("f9ebdfd6-1066-475a-8b72-d51ef3ceadb8")]] IReprojectionStereo : +class XPCF_CLIENTUUID("6bb5443e-ffa3-47f1-9276-54577fcd5368") XPCF_SERVERUUID("f9ebdfd6-1066-475a-8b72-d51ef3ceadb8") IReprojectionStereo : virtual public org::bcom::xpcf::IComponentIntrospect { public: /// @brief IReprojectionStereo constructor diff --git a/interfaces/api/geom/IUndistortPoints.h b/interfaces/api/geom/IUndistortPoints.h index 9167d999..becaba57 100644 --- a/interfaces/api/geom/IUndistortPoints.h +++ b/interfaces/api/geom/IUndistortPoints.h @@ -33,7 +33,7 @@ namespace geom { * UUID: a345a1d2-c3f3-497f-948b-cd1a199e6657 */ -class [[xpcf::clientUUID("9833188d-b7c6-4600-9032-35b0c4119eea")]] [[xpcf::serverUUID("def64009-6792-4e4f-b467-d17309232147")]] IUndistortPoints : +class XPCF_CLIENTUUID("9833188d-b7c6-4600-9032-35b0c4119eea") XPCF_SERVERUUID("def64009-6792-4e4f-b467-d17309232147") IUndistortPoints : virtual public org::bcom::xpcf::IComponentIntrospect { public: /// @brief IUndistortPoints default constructor diff --git a/interfaces/api/geom/IUnproject.h b/interfaces/api/geom/IUnproject.h index 28b2ff38..f742adea 100644 --- a/interfaces/api/geom/IUnproject.h +++ b/interfaces/api/geom/IUnproject.h @@ -33,7 +33,7 @@ namespace geom { * UUID: 21113a74-de60-4a3c-8b65-f3112beb3dc6 */ -class [[xpcf::clientUUID("7e71a7db-6a67-4c28-ad40-1922370fdc00")]] [[xpcf::serverUUID("10dc5091-bf42-4a0d-8573-0a099220da39")]] IUnproject : +class XPCF_CLIENTUUID("7e71a7db-6a67-4c28-ad40-1922370fdc00") XPCF_SERVERUUID("10dc5091-bf42-4a0d-8573-0a099220da39") IUnproject : virtual public org::bcom::xpcf::IComponentIntrospect { public: /// @brief IUnproject default constructor diff --git a/interfaces/api/image/IImageConvertor.h b/interfaces/api/image/IImageConvertor.h index 041fd752..95e6c7cc 100644 --- a/interfaces/api/image/IImageConvertor.h +++ b/interfaces/api/image/IImageConvertor.h @@ -33,7 +33,7 @@ namespace image { * @brief Converts image with a specific layout. * UUID: 9c982719-6cb4-4831-aa88-9e01afacbd16 */ -class [[xpcf::clientUUID("1977563c-c43f-4e5f-8df2-464d162889c3")]] [[xpcf::serverUUID("36458944-2986-49be-8ebf-55f2d12cc9dc")]] IImageConvertor : +class XPCF_CLIENTUUID("1977563c-c43f-4e5f-8df2-464d162889c3") XPCF_SERVERUUID("36458944-2986-49be-8ebf-55f2d12cc9dc") IImageConvertor : virtual public org::bcom::xpcf::IComponentIntrospect { public: IImageConvertor() = default; diff --git a/interfaces/api/image/IImageFilter.h b/interfaces/api/image/IImageFilter.h index 8f27affc..7e230321 100644 --- a/interfaces/api/image/IImageFilter.h +++ b/interfaces/api/image/IImageFilter.h @@ -31,7 +31,7 @@ namespace image { * UUID: f7948ae2-e994-416f-be40-dd404ca03a83 * */ -class [[xpcf::clientUUID("4b446acb-eb14-4f06-952d-722dd21ee4da")]] [[xpcf::serverUUID("639e76f5-322c-4599-a72c-bc8cfa2ceae3")]] IImageFilter : +class XPCF_CLIENTUUID("4b446acb-eb14-4f06-952d-722dd21ee4da") XPCF_SERVERUUID("639e76f5-322c-4599-a72c-bc8cfa2ceae3") IImageFilter : virtual public org::bcom::xpcf::IComponentIntrospect { public: IImageFilter() = default; diff --git a/interfaces/api/image/IImageLoader.h b/interfaces/api/image/IImageLoader.h index 4aae8888..e30a65b4 100644 --- a/interfaces/api/image/IImageLoader.h +++ b/interfaces/api/image/IImageLoader.h @@ -32,7 +32,7 @@ namespace image { * UUID: 6fcdaa8d-6ea9-4c3f-97b0-46cd11b67a9b * */ -class [[xpcf::clientUUID("abafe791-48df-4120-a164-b0bbfbc7bd81")]] [[xpcf::serverUUID("a37a908e-5c62-4083-b45c-2a81b7fb9a8d")]] IImageLoader : +class XPCF_CLIENTUUID("abafe791-48df-4120-a164-b0bbfbc7bd81") XPCF_SERVERUUID("a37a908e-5c62-4083-b45c-2a81b7fb9a8d") IImageLoader : virtual public org::bcom::xpcf::IComponentIntrospect { public: virtual ~IImageLoader() = default; diff --git a/interfaces/api/image/IImageRectification.h b/interfaces/api/image/IImageRectification.h index deead31c..89e6819c 100644 --- a/interfaces/api/image/IImageRectification.h +++ b/interfaces/api/image/IImageRectification.h @@ -31,7 +31,7 @@ namespace image { * @brief Rectify image. * UUID: f3e2cdb3-1818-4316-b536-a35650c59811 */ -class [[xpcf::clientUUID("9f68e2e0-33a6-4ce5-9b6e-bbe8088f9bc5")]] [[xpcf::serverUUID("f74f803c-4ea2-4420-962f-4803bc200da5")]] IImageRectification : +class XPCF_CLIENTUUID("9f68e2e0-33a6-4ce5-9b6e-bbe8088f9bc5") XPCF_SERVERUUID("f74f803c-4ea2-4420-962f-4803bc200da5") IImageRectification : virtual public org::bcom::xpcf::IComponentIntrospect { public: /// @brief IImageRectification constructor diff --git a/interfaces/api/image/IPerspectiveController.h b/interfaces/api/image/IPerspectiveController.h index 33406f4a..d5687e98 100644 --- a/interfaces/api/image/IPerspectiveController.h +++ b/interfaces/api/image/IPerspectiveController.h @@ -33,7 +33,7 @@ namespace image { * UUID: 4a7d5c34-cd6e-11e7-abc4-cec278b6b50a * */ -class [[xpcf::clientUUID("de8ab6b1-73c1-4954-8839-f37c63a5ac18")]] [[xpcf::serverUUID("35c1c15f-1151-45a5-b75c-012f985cb045")]] IPerspectiveController : +class XPCF_CLIENTUUID("de8ab6b1-73c1-4954-8839-f37c63a5ac18") XPCF_SERVERUUID("35c1c15f-1151-45a5-b75c-012f985cb045") IPerspectiveController : virtual public org::bcom::xpcf::IComponentIntrospect { public: /// @brief IPerspectiveController default constructor diff --git a/interfaces/api/input/devices/IARDevice.h b/interfaces/api/input/devices/IARDevice.h index a627c684..7e374264 100644 --- a/interfaces/api/input/devices/IARDevice.h +++ b/interfaces/api/input/devices/IARDevice.h @@ -19,7 +19,7 @@ namespace devices { * * This class describes the interface for retrieving data from a AR device that provides. */ -class [[xpcf::clientUUID("33dd6e3b-3fb5-449f-b90b-9fd97c59227c")]] [[xpcf::serverUUID("98ce0f5b-a279-4eae-95a9-798bf8c54a33")]] IARDevice : +class XPCF_CLIENTUUID("33dd6e3b-3fb5-449f-b90b-9fd97c59227c") XPCF_SERVERUUID("98ce0f5b-a279-4eae-95a9-798bf8c54a33") IARDevice : virtual public IDevice { public: /// @brief Specify the IARDevice constructor class diff --git a/interfaces/api/input/devices/ICamera.h b/interfaces/api/input/devices/ICamera.h index 7360e74e..4cbb7be1 100644 --- a/interfaces/api/input/devices/ICamera.h +++ b/interfaces/api/input/devices/ICamera.h @@ -34,7 +34,7 @@ namespace devices { * * This class describes the interface of a camera capture device. */ -class [[xpcf::clientUUID("dcd976a6-3f65-4c8b-8126-e00ad6a49212")]] [[xpcf::serverUUID("84cf5434-d8bb-4aa5-a518-a4d369161e0b")]] ICamera : +class XPCF_CLIENTUUID("dcd976a6-3f65-4c8b-8126-e00ad6a49212") XPCF_SERVERUUID("84cf5434-d8bb-4aa5-a518-a4d369161e0b") ICamera : virtual public IDevice { public: /// @brief Specify the ICamera constructor class diff --git a/interfaces/api/input/devices/ICameraCalibration.h b/interfaces/api/input/devices/ICameraCalibration.h index ad277f48..6495361e 100644 --- a/interfaces/api/input/devices/ICameraCalibration.h +++ b/interfaces/api/input/devices/ICameraCalibration.h @@ -31,7 +31,7 @@ namespace devices { * @brief Calibrates a camera. * UUID: 0e83b228-b9ca-413d-9dc2-db45c427428b */ -class [[xpcf::clientUUID("b3774427-f712-483b-bbed-060d2ce6134a")]] [[xpcf::serverUUID("ee5fc0d6-281e-4185-9898-c41606a7a0fc")]] ICameraCalibration : +class XPCF_CLIENTUUID("b3774427-f712-483b-bbed-060d2ce6134a") XPCF_SERVERUUID("ee5fc0d6-281e-4185-9898-c41606a7a0fc") ICameraCalibration : virtual public org::bcom::xpcf::IComponentIntrospect { public: /// @brief ~ICameraCalibration diff --git a/interfaces/api/input/devices/IDepthCamera.h b/interfaces/api/input/devices/IDepthCamera.h index d382e50f..7122f9c2 100644 --- a/interfaces/api/input/devices/IDepthCamera.h +++ b/interfaces/api/input/devices/IDepthCamera.h @@ -34,7 +34,7 @@ namespace devices { * * This class describes the interface of a depth camera capture device. */ -class [[xpcf::clientUUID("d1c62c3a-6d98-4bf7-b2f8-5eba94979a9d")]] [[xpcf::serverUUID("83df6a42-88e9-4895-8b95-cfcfe1b6911c")]] IDepthCamera : +class XPCF_CLIENTUUID("d1c62c3a-6d98-4bf7-b2f8-5eba94979a9d") XPCF_SERVERUUID("83df6a42-88e9-4895-8b95-cfcfe1b6911c") IDepthCamera : virtual public IDevice { public: /// @brief Specify the IDepthCamera constructor class diff --git a/interfaces/api/input/devices/IDevice.h b/interfaces/api/input/devices/IDevice.h index da077539..bf8288b3 100644 --- a/interfaces/api/input/devices/IDevice.h +++ b/interfaces/api/input/devices/IDevice.h @@ -33,7 +33,7 @@ namespace devices { * * This class describes the interface of a capture device. */ -class [[xpcf::clientUUID("abd028ed-44a2-4ac0-831b-e0e9b939031c")]] [[xpcf::serverUUID("f20a4533-57e9-4a76-893a-3c031e267409")]] IDevice: +class XPCF_CLIENTUUID("abd028ed-44a2-4ac0-831b-e0e9b939031c") XPCF_SERVERUUID("f20a4533-57e9-4a76-893a-3c031e267409") IDevice: virtual public org::bcom::xpcf::IComponentIntrospect { public: diff --git a/interfaces/api/input/devices/IIMU.h b/interfaces/api/input/devices/IIMU.h index 88fb47c1..c3ac3823 100644 --- a/interfaces/api/input/devices/IIMU.h +++ b/interfaces/api/input/devices/IIMU.h @@ -33,7 +33,7 @@ namespace devices { * * This class describes the interface of an Inertial Measurement Unit capture device. */ -class [[xpcf::clientUUID("fb1332ea-5f0a-4d7e-8080-db9b6171769e")]] [[xpcf::serverUUID("0b360851-0cdd-43d1-91db-d925218d0917")]] IIMU : +class XPCF_CLIENTUUID("fb1332ea-5f0a-4d7e-8080-db9b6171769e") XPCF_SERVERUUID("0b360851-0cdd-43d1-91db-d925218d0917") IIMU : virtual public IDevice { public: /// @brief IIMU default constructor diff --git a/interfaces/api/input/devices/IRGBDCamera.h b/interfaces/api/input/devices/IRGBDCamera.h index ed8f61b9..0a02cc70 100644 --- a/interfaces/api/input/devices/IRGBDCamera.h +++ b/interfaces/api/input/devices/IRGBDCamera.h @@ -34,7 +34,7 @@ namespace devices { * * This class describes the interface of a RGBD camera capture device. */ -class [[xpcf::clientUUID("1c8df185-f8d9-4899-8206-74d1f64a7ad9")]] [[xpcf::serverUUID("01bb552a-9e6c-47fe-8b57-bce2a4c0ce42")]] IRGBDCamera : +class XPCF_CLIENTUUID("1c8df185-f8d9-4899-8206-74d1f64a7ad9") XPCF_SERVERUUID("01bb552a-9e6c-47fe-8b57-bce2a4c0ce42") IRGBDCamera : virtual public ICamera, virtual public IDepthCamera { public: /// @brief Specify the IRGBDCamera constructor class diff --git a/interfaces/api/input/devices/IStereoCameraCalibration.h b/interfaces/api/input/devices/IStereoCameraCalibration.h index 81fa1723..4eb6ada2 100644 --- a/interfaces/api/input/devices/IStereoCameraCalibration.h +++ b/interfaces/api/input/devices/IStereoCameraCalibration.h @@ -31,7 +31,7 @@ namespace devices { * @brief Calibrate and rectify a stereo camera. * UUID: b4fad0ff-c636-492e-ba12-710927a760c7 */ -class [[xpcf::clientUUID("f2cec917-6793-4aef-90cb-fd3f843fb43e")]] [[xpcf::serverUUID("d8ac896d-772d-4ce1-b7be-a8f08020eeb6")]] IStereoCameraCalibration : +class XPCF_CLIENTUUID("f2cec917-6793-4aef-90cb-fd3f843fb43e") XPCF_SERVERUUID("d8ac896d-772d-4ce1-b7be-a8f08020eeb6") IStereoCameraCalibration : virtual public org::bcom::xpcf::IComponentIntrospect { public: /// @brief IStereoCameraCalibration constructor diff --git a/interfaces/api/input/files/IMeshLoader.h b/interfaces/api/input/files/IMeshLoader.h index dfc11e5a..b4695a43 100644 --- a/interfaces/api/input/files/IMeshLoader.h +++ b/interfaces/api/input/files/IMeshLoader.h @@ -31,7 +31,7 @@ namespace files { * UUID: 315c7cd4-462d-11ed-b878-0242ac120002 * */ -class [[xpcf::clientUUID("5580de7a-462d-11ed-b878-0242ac120002")]] [[xpcf::serverUUID("5973d118-462d-11ed-b878-0242ac120002")]] IMeshLoader : +class XPCF_CLIENTUUID("5580de7a-462d-11ed-b878-0242ac120002") XPCF_SERVERUUID("5973d118-462d-11ed-b878-0242ac120002") IMeshLoader : virtual public org::bcom::xpcf::IComponentIntrospect { public: IMeshLoader() = default; diff --git a/interfaces/api/input/files/IPointCloudLoader.h b/interfaces/api/input/files/IPointCloudLoader.h index 5a71abbb..b7bf58d5 100644 --- a/interfaces/api/input/files/IPointCloudLoader.h +++ b/interfaces/api/input/files/IPointCloudLoader.h @@ -31,7 +31,7 @@ namespace files { * UUID: 1abd8117-87d3-4c6c-8fb6-c2fdb7359ee2 * */ -class [[xpcf::clientUUID("dd80a6fa-db2f-4ba7-ba69-5207a68cfb03")]] [[xpcf::serverUUID("19780d21-e6a8-4f28-bf63-483f50b2af9d")]] IPointCloudLoader : +class XPCF_CLIENTUUID("dd80a6fa-db2f-4ba7-ba69-5207a68cfb03") XPCF_SERVERUUID("19780d21-e6a8-4f28-bf63-483f50b2af9d") IPointCloudLoader : virtual public org::bcom::xpcf::IComponentIntrospect { public: IPointCloudLoader() = default; diff --git a/interfaces/api/input/files/ITrackableLoader.h b/interfaces/api/input/files/ITrackableLoader.h index 29422cdd..f6be4918 100644 --- a/interfaces/api/input/files/ITrackableLoader.h +++ b/interfaces/api/input/files/ITrackableLoader.h @@ -32,7 +32,7 @@ namespace files { * UUID: 8e54d5d0-f7a3-4d62-b012-728e5704b46a * */ -class [[xpcf::clientUUID("7f62f9da-c21c-44fe-aebe-fedca94f6be6")]] [[xpcf::serverUUID("9361175d-d517-4a54-ac49-e41610b6d64f")]] ITrackableLoader : +class XPCF_CLIENTUUID("7f62f9da-c21c-44fe-aebe-fedca94f6be6") XPCF_SERVERUUID("9361175d-d517-4a54-ac49-e41610b6d64f") ITrackableLoader : virtual public org::bcom::xpcf::IComponentIntrospect { public: ITrackableLoader() = default; diff --git a/interfaces/api/input/files/IWorldGraphLoader.h b/interfaces/api/input/files/IWorldGraphLoader.h index b1c22199..c47a4a87 100644 --- a/interfaces/api/input/files/IWorldGraphLoader.h +++ b/interfaces/api/input/files/IWorldGraphLoader.h @@ -34,7 +34,7 @@ namespace files { * UUID: b68a0544-c9f2-48eb-9542-c2048ff25c08 * */ -class [[xpcf::clientUUID("1dd71248-747b-4a90-b2c6-7811aed57ba0")]] [[xpcf::serverUUID("15716f60-7688-44cb-867c-a8a49d4b9a80")]] IWorldGraphLoader : +class XPCF_CLIENTUUID("1dd71248-747b-4a90-b2c6-7811aed57ba0") XPCF_SERVERUUID("15716f60-7688-44cb-867c-a8a49d4b9a80") IWorldGraphLoader : virtual public org::bcom::xpcf::IComponentIntrospect { public: IWorldGraphLoader() = default; diff --git a/interfaces/api/loop/ILoopClosureDetector.h b/interfaces/api/loop/ILoopClosureDetector.h index faebe209..c02100a0 100644 --- a/interfaces/api/loop/ILoopClosureDetector.h +++ b/interfaces/api/loop/ILoopClosureDetector.h @@ -33,7 +33,7 @@ namespace loop { * UUID: a267c93a-c1c6-11ea-b3de-0242ac130004 */ -class [[xpcf::clientUUID("ee57ff66-30d0-11ec-8d3d-0242ac130003")]] [[xpcf::serverUUID("fd612992-30d0-11ec-8d3d-0242ac130003")]] ILoopClosureDetector : +class XPCF_CLIENTUUID("ee57ff66-30d0-11ec-8d3d-0242ac130003") XPCF_SERVERUUID("fd612992-30d0-11ec-8d3d-0242ac130003") ILoopClosureDetector : virtual public org::bcom::xpcf::IComponentIntrospect { public: ///@brief ILoopClosureDetector default constructor diff --git a/interfaces/api/loop/ILoopCorrector.h b/interfaces/api/loop/ILoopCorrector.h index aa4af8d0..9eeba651 100644 --- a/interfaces/api/loop/ILoopCorrector.h +++ b/interfaces/api/loop/ILoopCorrector.h @@ -33,7 +33,7 @@ namespace loop{ * UUID: 8f05eea8-c1c6-11ea-b3de-0242ac130004 */ -class [[xpcf::clientUUID("51f449f8-c9df-4c3a-ac57-7ca95debfdbc")]] [[xpcf::serverUUID("7dc30f5b-c61f-4eea-81d9-265a2a2b3b93")]] ILoopCorrector : +class XPCF_CLIENTUUID("51f449f8-c9df-4c3a-ac57-7ca95debfdbc") XPCF_SERVERUUID("7dc30f5b-c61f-4eea-81d9-265a2a2b3b93") ILoopCorrector : virtual public org::bcom::xpcf::IComponentIntrospect { public: ///@brief ILoopCorrector default constructor diff --git a/interfaces/api/loop/IOverlapDetector.h b/interfaces/api/loop/IOverlapDetector.h index d7ba7b0b..8c98e07e 100644 --- a/interfaces/api/loop/IOverlapDetector.h +++ b/interfaces/api/loop/IOverlapDetector.h @@ -33,7 +33,7 @@ namespace loop { * UUID: fe6a40ca-137c-11eb-adc1-0242ac120002 */ -class [[xpcf::clientUUID("ccc5e7f8-2f9c-4b2f-a7f1-f151a9aa2191")]] [[xpcf::serverUUID("1befd83d-c1b4-4bee-acab-5b63e371c788")]] IOverlapDetector : +class XPCF_CLIENTUUID("ccc5e7f8-2f9c-4b2f-a7f1-f151a9aa2191") XPCF_SERVERUUID("1befd83d-c1b4-4bee-acab-5b63e371c788") IOverlapDetector : virtual public org::bcom::xpcf::IComponentIntrospect { public: ///@brief IOverlapDetector default constructor diff --git a/interfaces/api/output/files/IMeshExporter.h b/interfaces/api/output/files/IMeshExporter.h index 5baf6252..c720dc7f 100644 --- a/interfaces/api/output/files/IMeshExporter.h +++ b/interfaces/api/output/files/IMeshExporter.h @@ -31,7 +31,7 @@ namespace SolAR::api::output::files * UUID: faf50760-462c-11ed-b878-0242ac120002 * */ -class [[xpcf::clientUUID("0e1263d8-462d-11ed-b878-0242ac120002")]] [[xpcf::serverUUID("14cbf040-462d-11ed-b878-0242ac120002")]] IMeshExporter : +class XPCF_CLIENTUUID("0e1263d8-462d-11ed-b878-0242ac120002") XPCF_SERVERUUID("14cbf040-462d-11ed-b878-0242ac120002") IMeshExporter : virtual public org::bcom::xpcf::IComponentIntrospect { public: IMeshExporter() = default; diff --git a/interfaces/api/output/files/IPointCloudExporter.h b/interfaces/api/output/files/IPointCloudExporter.h index ed4b0afc..218ebc3d 100644 --- a/interfaces/api/output/files/IPointCloudExporter.h +++ b/interfaces/api/output/files/IPointCloudExporter.h @@ -31,7 +31,7 @@ namespace SolAR::api::output::files * UUID: 8e2ec8f9-ed99-473d-84eb-7cb35eff6a1e * */ -class [[xpcf::clientUUID("7d924b06-238c-11ed-861d-0242ac120002")]] [[xpcf::serverUUID("858c7124-238c-11ed-861d-0242ac120002")]] IPointCloudExporter : +class XPCF_CLIENTUUID("7d924b06-238c-11ed-861d-0242ac120002") XPCF_SERVERUUID("858c7124-238c-11ed-861d-0242ac120002") IPointCloudExporter : virtual public org::bcom::xpcf::IComponentIntrospect { public: IPointCloudExporter() = default; diff --git a/interfaces/api/pipeline/IAsyncRelocalizationPipeline.h b/interfaces/api/pipeline/IAsyncRelocalizationPipeline.h index cbf614d6..0b3978dc 100644 --- a/interfaces/api/pipeline/IAsyncRelocalizationPipeline.h +++ b/interfaces/api/pipeline/IAsyncRelocalizationPipeline.h @@ -67,7 +67,7 @@ typedef enum { * This class provides the interface to define an asynchronous relocalization processing pipeline. */ -class [[xpcf::clientUUID("91a569da-5695-11ec-bf63-0242ac130002")]] [[xpcf::serverUUID("95913e8e-5695-11ec-bf63-0242ac130002")]] IAsyncRelocalizationPipeline : +class XPCF_CLIENTUUID("91a569da-5695-11ec-bf63-0242ac130002") XPCF_SERVERUUID("95913e8e-5695-11ec-bf63-0242ac130002") IAsyncRelocalizationPipeline : virtual public IPipeline { public: /// @brief IAsyncRelocalizationPipeline default constructor diff --git a/interfaces/api/pipeline/IDenseMappingPipeline.h b/interfaces/api/pipeline/IDenseMappingPipeline.h index a768c0f8..42bca5fe 100644 --- a/interfaces/api/pipeline/IDenseMappingPipeline.h +++ b/interfaces/api/pipeline/IDenseMappingPipeline.h @@ -46,7 +46,7 @@ typedef enum { * This class provides the interface to define a dense mapping processing pipeline. */ -class [[xpcf::clientUUID("54fc1ed0-480b-11ed-b878-0242ac120002")]] [[xpcf::serverUUID("5ac9298e-480b-11ed-b878-0242ac120002")]] +class XPCF_CLIENTUUID("54fc1ed0-480b-11ed-b878-0242ac120002") XPCF_SERVERUUID("5ac9298e-480b-11ed-b878-0242ac120002") #ifndef DOXYGEN_SHOULD_SKIP_THIS // Doxygen does not support custom DSL XPCF_GRPC_CLIENT_RECV_SIZE("-1") XPCF_GRPC_CLIENT_SEND_SIZE("-1") #endif diff --git a/interfaces/api/pipeline/IMapUpdatePipeline.h b/interfaces/api/pipeline/IMapUpdatePipeline.h index 2c9a5ce4..f57db667 100644 --- a/interfaces/api/pipeline/IMapUpdatePipeline.h +++ b/interfaces/api/pipeline/IMapUpdatePipeline.h @@ -35,7 +35,7 @@ namespace pipeline { * This class provides the interface to define a map update pipeline. */ -class [[xpcf::clientUUID("d9da863c-c9ff-4562-a3a2-329ac1f44008")]] [[xpcf::serverUUID("82f9fdff-06ee-471f-a260-b7f4ac414627")]] +class XPCF_CLIENTUUID("d9da863c-c9ff-4562-a3a2-329ac1f44008") XPCF_SERVERUUID("82f9fdff-06ee-471f-a260-b7f4ac414627") #ifndef DOXYGEN_SHOULD_SKIP_THIS // Doxygen does not support custom DSL XPCF_GRPC_CLIENT_RECV_SIZE("-1") XPCF_GRPC_CLIENT_SEND_SIZE("-1") #endif diff --git a/interfaces/api/pipeline/IMappingPipeline.h b/interfaces/api/pipeline/IMappingPipeline.h index fe6c3333..ab5cf248 100644 --- a/interfaces/api/pipeline/IMappingPipeline.h +++ b/interfaces/api/pipeline/IMappingPipeline.h @@ -49,7 +49,7 @@ typedef enum { * This class provides the interface to define a mapping processing pipeline. */ -class [[xpcf::clientUUID("110a089c-0bb1-488e-b24b-c1b96bc9df3b")]] [[xpcf::serverUUID("aced265d-832c-44e3-9356-dab531fa153a")]] +class XPCF_CLIENTUUID("110a089c-0bb1-488e-b24b-c1b96bc9df3b") XPCF_SERVERUUID("aced265d-832c-44e3-9356-dab531fa153a") #ifndef DOXYGEN_SHOULD_SKIP_THIS // Doxygen does not support custom DSL XPCF_GRPC_CLIENT_RECV_SIZE("-1") #endif diff --git a/interfaces/api/pipeline/IRelocalizationPipeline.h b/interfaces/api/pipeline/IRelocalizationPipeline.h index 03f0dd6e..c4cc1c04 100644 --- a/interfaces/api/pipeline/IRelocalizationPipeline.h +++ b/interfaces/api/pipeline/IRelocalizationPipeline.h @@ -37,7 +37,7 @@ namespace pipeline { * This class provides the interface to define a relocalization processing pipeline. */ -class [[xpcf::clientUUID("597d510d-452a-4da2-9c3a-8d4b8d15c584")]] [[xpcf::serverUUID("234bb765-ac3b-4755-8825-5cd92145b7a8")]] +class XPCF_CLIENTUUID("597d510d-452a-4da2-9c3a-8d4b8d15c584") XPCF_SERVERUUID("234bb765-ac3b-4755-8825-5cd92145b7a8") #ifndef DOXYGEN_SHOULD_SKIP_THIS // Doxygen does not support custom DSL XPCF_GRPC_CLIENT_RECV_SIZE("-1") XPCF_GRPC_CLIENT_SEND_SIZE("-1") #endif diff --git a/interfaces/api/pipeline/IServiceManagerPipeline.h b/interfaces/api/pipeline/IServiceManagerPipeline.h index 5089fec9..2a7f1d0d 100644 --- a/interfaces/api/pipeline/IServiceManagerPipeline.h +++ b/interfaces/api/pipeline/IServiceManagerPipeline.h @@ -44,7 +44,7 @@ enum class ServiceType { * This class provides the interface to define a manager for all SolAR remote services. */ -class [[xpcf::clientUUID("600ca5f4-6432-11ed-81ce-0242ac120002")]] [[xpcf::serverUUID("65c3a736-6432-11ed-81ce-0242ac120002")]] IServiceManagerPipeline : +class XPCF_CLIENTUUID("600ca5f4-6432-11ed-81ce-0242ac120002") XPCF_SERVERUUID("65c3a736-6432-11ed-81ce-0242ac120002") IServiceManagerPipeline : virtual public IPipeline { public: /// @brief IServiceManagerPipeline default constructor diff --git a/interfaces/api/pointCloud/IPCFilter.h b/interfaces/api/pointCloud/IPCFilter.h index ef9ea96f..cc07f80f 100644 --- a/interfaces/api/pointCloud/IPCFilter.h +++ b/interfaces/api/pointCloud/IPCFilter.h @@ -31,7 +31,7 @@ namespace pointCloud { * UUID: 3e068943-5230-4e6c-abd7-959f293f9829 */ -class [[xpcf::clientUUID("34192941-748e-4521-8d30-e12c06f5e226")]] [[xpcf::serverUUID("44842913-0e76-44bc-84ae-c8a0850ac97e")]] IPCFilter : +class XPCF_CLIENTUUID("34192941-748e-4521-8d30-e12c06f5e226") XPCF_SERVERUUID("44842913-0e76-44bc-84ae-c8a0850ac97e") IPCFilter : virtual public org::bcom::xpcf::IComponentIntrospect { public: /// @brief IPCFilter default constructor diff --git a/interfaces/api/pointCloud/IPCFilterCentroid.h b/interfaces/api/pointCloud/IPCFilterCentroid.h index 9f0d2fd9..2fbc8441 100644 --- a/interfaces/api/pointCloud/IPCFilterCentroid.h +++ b/interfaces/api/pointCloud/IPCFilterCentroid.h @@ -34,7 +34,7 @@ namespace pointCloud { * This class provides a filtering method to prune a point cloud according to a given 3D point. */ -class [[xpcf::clientUUID("1c9544b4-5b79-44fa-a9fe-82d1d94a00c8")]] [[xpcf::serverUUID("97aad71f-ce23-4015-bded-2c31f1aeb312")]] IPCFilterCentroid : +class XPCF_CLIENTUUID("1c9544b4-5b79-44fa-a9fe-82d1d94a00c8") XPCF_SERVERUUID("97aad71f-ce23-4015-bded-2c31f1aeb312") IPCFilterCentroid : virtual public org::bcom::xpcf::IComponentIntrospect { public: /// @brief IPCFilterCentroid default constructor diff --git a/interfaces/api/reloc/IRegression.h b/interfaces/api/reloc/IRegression.h index 5a913469..cafa3c42 100644 --- a/interfaces/api/reloc/IRegression.h +++ b/interfaces/api/reloc/IRegression.h @@ -36,7 +36,7 @@ namespace reloc { * This class provides a solution to learn and define a set of 3D world coordinates corresponding to a set of 2D descriptors. */ -class [[xpcf::clientUUID("8dc16e57-5f95-474b-8ff8-bb7570e02230")]] [[xpcf::serverUUID("d991baa9-3e57-4377-b244-7690091cea9e")]] IRegression : +class XPCF_CLIENTUUID("8dc16e57-5f95-474b-8ff8-bb7570e02230") XPCF_SERVERUUID("d991baa9-3e57-4377-b244-7690091cea9e") IRegression : virtual public org::bcom::xpcf::IComponentIntrospect { public: ///@brief IRegression default constructor. diff --git a/interfaces/api/reloc/IRelocalizer.h b/interfaces/api/reloc/IRelocalizer.h index dcced93a..700ea95c 100644 --- a/interfaces/api/reloc/IRelocalizer.h +++ b/interfaces/api/reloc/IRelocalizer.h @@ -34,7 +34,7 @@ namespace reloc { * This class provides a solution to get the pose given a frame. */ -class [[xpcf::clientUUID("fcbc25a8-d706-4a80-9d18-820bebbe45d6")]] [[xpcf::serverUUID("cc39b0cc-9236-46b2-8188-937992010c9f")]] IRelocalizer : +class XPCF_CLIENTUUID("fcbc25a8-d706-4a80-9d18-820bebbe45d6") XPCF_SERVERUUID("cc39b0cc-9236-46b2-8188-937992010c9f") IRelocalizer : virtual public org::bcom::xpcf::IComponentIntrospect { public: ///@brief IRelocalizer default constructor. diff --git a/interfaces/api/segm/IInstanceSegmentation.h b/interfaces/api/segm/IInstanceSegmentation.h index a81cbe06..04282d72 100644 --- a/interfaces/api/segm/IInstanceSegmentation.h +++ b/interfaces/api/segm/IInstanceSegmentation.h @@ -32,7 +32,7 @@ namespace segm { * UUID: 402aae34-bbec-43e3-8f36-3f201b6ca6d2 */ -class [[xpcf::clientUUID("e75921b5-8b50-44a9-a488-edf1608c8f3e")]] [[xpcf::serverUUID("e85b2140-3cdd-422c-9ca9-b98c99237abd")]] IInstanceSegmentation : +class XPCF_CLIENTUUID("e75921b5-8b50-44a9-a488-edf1608c8f3e") XPCF_SERVERUUID("e85b2140-3cdd-422c-9ca9-b98c99237abd") IInstanceSegmentation : virtual public org::bcom::xpcf::IComponentIntrospect { public: ///@brief IInstanceSegmentation default constructor. diff --git a/interfaces/api/segm/IPanopticSegmentation.h b/interfaces/api/segm/IPanopticSegmentation.h index 1d45fe74..65436481 100644 --- a/interfaces/api/segm/IPanopticSegmentation.h +++ b/interfaces/api/segm/IPanopticSegmentation.h @@ -32,7 +32,7 @@ namespace segm { * UUID: 60701300-75e2-4215-a5e1-3a2b0aa3193a */ -class [[xpcf::clientUUID("26e61305-b483-487a-8701-4a9612af5db6")]] [[xpcf::serverUUID("5c3e0d59-101c-40f8-8efe-0190c4816d81")]] IPanopticSegmentation : +class XPCF_CLIENTUUID("26e61305-b483-487a-8701-4a9612af5db6") XPCF_SERVERUUID("5c3e0d59-101c-40f8-8efe-0190c4816d81") IPanopticSegmentation : virtual public org::bcom::xpcf::IComponentIntrospect { public: ///@brief IPanopticSegmentation default constructor. diff --git a/interfaces/api/segm/ISemanticSegmentation.h b/interfaces/api/segm/ISemanticSegmentation.h index 596b2886..1644301f 100644 --- a/interfaces/api/segm/ISemanticSegmentation.h +++ b/interfaces/api/segm/ISemanticSegmentation.h @@ -32,7 +32,7 @@ namespace segm { * UUID: 2fd30b7c-c6e4-4af7-a711-0b69964e68c2 */ -class [[xpcf::clientUUID("fb4b42d6-95a9-48a4-a86f-2c588b964f73")]] [[xpcf::serverUUID("97417d56-f5ae-4a4a-b72f-aab1185f49a0")]] ISemanticSegmentation : +class XPCF_CLIENTUUID("fb4b42d6-95a9-48a4-a86f-2c588b964f73") XPCF_SERVERUUID("97417d56-f5ae-4a4a-b72f-aab1185f49a0") ISemanticSegmentation : virtual public org::bcom::xpcf::IComponentIntrospect { public: ///@brief ISemanticSegmentation default constructor. diff --git a/interfaces/api/slam/IBootstrapper.h b/interfaces/api/slam/IBootstrapper.h index b0190938..eb21066c 100644 --- a/interfaces/api/slam/IBootstrapper.h +++ b/interfaces/api/slam/IBootstrapper.h @@ -36,7 +36,7 @@ namespace slam { * UUID: b0515c62-cc81-4600-835c-8acdfedf39b5 */ -class [[xpcf::clientUUID("d593b615-efcf-4b4c-82eb-148065f85008")]] [[xpcf::serverUUID("a7509f5c-f214-408d-be3a-acb38dd8512b")]] IBootstrapper : +class XPCF_CLIENTUUID("d593b615-efcf-4b4c-82eb-148065f85008") XPCF_SERVERUUID("a7509f5c-f214-408d-be3a-acb38dd8512b") IBootstrapper : virtual public org::bcom::xpcf::IComponentIntrospect { public: /// @brief IBootstrapper default constructor diff --git a/interfaces/api/slam/IMapping.h b/interfaces/api/slam/IMapping.h index c67c783e..0b750c29 100644 --- a/interfaces/api/slam/IMapping.h +++ b/interfaces/api/slam/IMapping.h @@ -35,7 +35,7 @@ namespace slam { * UUID: 33db5a56-9be2-4e5a-8fdc-de25e1633cf6 */ -class [[xpcf::clientUUID("9edd1642-4b42-4c08-a11f-e46839f7fd63")]] [[xpcf::serverUUID("352d5136-b5eb-4ee6-bfbd-012cb23e935d")]] IMapping : +class XPCF_CLIENTUUID("9edd1642-4b42-4c08-a11f-e46839f7fd63") XPCF_SERVERUUID("352d5136-b5eb-4ee6-bfbd-012cb23e935d") IMapping : virtual public org::bcom::xpcf::IComponentIntrospect { public: /// @brief IMapping default constructor diff --git a/interfaces/api/slam/ITracking.h b/interfaces/api/slam/ITracking.h index 728b0876..9cdc6c15 100644 --- a/interfaces/api/slam/ITracking.h +++ b/interfaces/api/slam/ITracking.h @@ -35,7 +35,7 @@ namespace slam { * UUID: c2182b8e-03e9-43a3-a5b9-326e80554cf8 */ -class [[xpcf::clientUUID("064ae968-4fc7-448b-a485-468a112e4fa3")]] [[xpcf::serverUUID("d5baf1c5-d0ff-40ba-aa45-2c308a402587")]] ITracking : +class XPCF_CLIENTUUID("064ae968-4fc7-448b-a485-468a112e4fa3") XPCF_SERVERUUID("d5baf1c5-d0ff-40ba-aa45-2c308a402587") ITracking : virtual public org::bcom::xpcf::IComponentIntrospect { public: /// @brief ITracking default constructor diff --git a/interfaces/api/solver/map/IBundler.h b/interfaces/api/solver/map/IBundler.h index 5ea7d253..2026c372 100644 --- a/interfaces/api/solver/map/IBundler.h +++ b/interfaces/api/solver/map/IBundler.h @@ -26,7 +26,7 @@ namespace map { * UUID: 35b9bdb7-d23c-4909-984f-ae7f9a292e6c */ -class [[xpcf::clientUUID("258dfecc-850e-4ec7-9b25-77c5bca8694a")]] [[xpcf::serverUUID("96d272a9-fbc8-4a77-83ad-63edd60a8065")]] IBundler : +class XPCF_CLIENTUUID("258dfecc-850e-4ec7-9b25-77c5bca8694a") XPCF_SERVERUUID("96d272a9-fbc8-4a77-83ad-63edd60a8065") IBundler : virtual public org::bcom::xpcf::IComponentIntrospect { public: /// @brief IBundler default constructor diff --git a/interfaces/api/solver/map/IMapFilter.h b/interfaces/api/solver/map/IMapFilter.h index 1e609e7f..c0677381 100644 --- a/interfaces/api/solver/map/IMapFilter.h +++ b/interfaces/api/solver/map/IMapFilter.h @@ -38,7 +38,7 @@ namespace map { * @brief Filters a map of 3D points. * UUID: 68dc9152-5199-11ea-8d77-2e728ce88125 */ -class [[xpcf::clientUUID("eae4a8bc-3780-4f62-823a-b69d2b92c87e")]] [[xpcf::serverUUID("c9be934a-fbb6-43d6-ae21-c30898a7ea6b")]] IMapFilter : +class XPCF_CLIENTUUID("eae4a8bc-3780-4f62-823a-b69d2b92c87e") XPCF_SERVERUUID("c9be934a-fbb6-43d6-ae21-c30898a7ea6b") IMapFilter : virtual public org::bcom::xpcf::IComponentIntrospect { public: /// @brief IMapFilter default constructor diff --git a/interfaces/api/solver/map/IMapUpdate.h b/interfaces/api/solver/map/IMapUpdate.h index 30fae8d1..9063c1bc 100644 --- a/interfaces/api/solver/map/IMapUpdate.h +++ b/interfaces/api/solver/map/IMapUpdate.h @@ -38,7 +38,7 @@ namespace map { * UUID: 943dd9a0-4889-489a-80a7-84be1a6c1650 */ -class [[xpcf::clientUUID("2c2b7702-6a34-4add-b645-547ef0185253")]] [[xpcf::serverUUID("4c496a20-693c-4729-93dc-7c2b06157604")]] IMapUpdate : +class XPCF_CLIENTUUID("2c2b7702-6a34-4add-b645-547ef0185253") XPCF_SERVERUUID("4c496a20-693c-4729-93dc-7c2b06157604") IMapUpdate : virtual public org::bcom::xpcf::IComponentIntrospect { public: /// @brief IMapUpdate default constructor diff --git a/interfaces/api/solver/map/ITriangulator.h b/interfaces/api/solver/map/ITriangulator.h index 26cc0e70..0573b5ac 100644 --- a/interfaces/api/solver/map/ITriangulator.h +++ b/interfaces/api/solver/map/ITriangulator.h @@ -38,7 +38,7 @@ namespace map { * @brief Triangulates a set of 2D-2D undistorted points correspondances with known respective camera poses. * UUID: 3a01b0e9-9a76-43f5-97b3-85bb6979b953 */ -class [[xpcf::clientUUID("1b6be40f-030c-4436-a920-913d6e4421f4")]] [[xpcf::serverUUID("9cb53cc2-2887-4606-8d07-d9d4ae3108b2")]] ITriangulator : +class XPCF_CLIENTUUID("1b6be40f-030c-4436-a920-913d6e4421f4") XPCF_SERVERUUID("9cb53cc2-2887-4606-8d07-d9d4ae3108b2") ITriangulator : virtual public org::bcom::xpcf::IComponentIntrospect { public: /// @brief ITriangulator default constructor diff --git a/interfaces/api/solver/pose/I2D3DCorrespondencesFinder.h b/interfaces/api/solver/pose/I2D3DCorrespondencesFinder.h index 0b3c2ce2..f4a8e366 100644 --- a/interfaces/api/solver/pose/I2D3DCorrespondencesFinder.h +++ b/interfaces/api/solver/pose/I2D3DCorrespondencesFinder.h @@ -37,7 +37,7 @@ namespace pose { * * Knowing a frame, its reference keyframe which already has 3D correpspondences, as well the 2D matches between them, the component find the 2d-3D correspondences between the current frame and the 3D Points visible from the reference keyframe. */ -class [[xpcf::clientUUID("5752dde3-a6b6-4828-83d9-914c9fe1954c")]] [[xpcf::serverUUID("c459012f-0923-400c-9340-b91b1525a7bb")]] I2D3DCorrespondencesFinder : +class XPCF_CLIENTUUID("5752dde3-a6b6-4828-83d9-914c9fe1954c") XPCF_SERVERUUID("c459012f-0923-400c-9340-b91b1525a7bb") I2D3DCorrespondencesFinder : virtual public org::bcom::xpcf::IComponentIntrospect { public: /// @brief I2D3DCorrespondencesFinder default constructor. diff --git a/interfaces/api/solver/pose/I2DTransformFinder.h b/interfaces/api/solver/pose/I2DTransformFinder.h index d0f64a47..3d9b66f2 100644 --- a/interfaces/api/solver/pose/I2DTransformFinder.h +++ b/interfaces/api/solver/pose/I2DTransformFinder.h @@ -42,7 +42,7 @@ namespace pose { * UUID: 45dd370a-0eab-4a7f-93d0-43453b4c7517 */ -class [[xpcf::clientUUID("bb9d839b-4304-44f3-ac09-b6d965e65b6e")]] [[xpcf::serverUUID("e59ed354-1ddc-4f89-b445-31001e0acc67")]] I2DTransformFinder : +class XPCF_CLIENTUUID("bb9d839b-4304-44f3-ac09-b6d965e65b6e") XPCF_SERVERUUID("e59ed354-1ddc-4f89-b445-31001e0acc67") I2DTransformFinder : virtual public org::bcom::xpcf::IComponentIntrospect { public: ///@brief I2DTransformFinder default constructor. diff --git a/interfaces/api/solver/pose/I2Dto3DTransformDecomposer.h b/interfaces/api/solver/pose/I2Dto3DTransformDecomposer.h index 8b1ecd55..86b64ce1 100644 --- a/interfaces/api/solver/pose/I2Dto3DTransformDecomposer.h +++ b/interfaces/api/solver/pose/I2Dto3DTransformDecomposer.h @@ -33,7 +33,7 @@ namespace pose { * * Knowing a frame, its reference keyframe which already has 3D correpspondences, as well the 2D matches between them, the component find the 2d-3D correspondences between the current frame and the 3D Points visible from the reference keyframe. * */ -class [[xpcf::clientUUID("861a828d-bdda-424b-a00b-3a6a7ef48f8e")]] [[xpcf::serverUUID("eded8db8-d32b-49bc-8b72-db936a63ec9f")]] I2Dto3DTransformDecomposer : +class XPCF_CLIENTUUID("861a828d-bdda-424b-a00b-3a6a7ef48f8e") XPCF_SERVERUUID("eded8db8-d32b-49bc-8b72-db936a63ec9f") I2Dto3DTransformDecomposer : virtual public org::bcom::xpcf::IComponentIntrospect { public: /// @brief I2Dto3DTransformDecomposer default constructor. diff --git a/interfaces/api/solver/pose/I2Dto3DTransformDecomposerValidation.h b/interfaces/api/solver/pose/I2Dto3DTransformDecomposerValidation.h index 077013b7..7da0ca71 100644 --- a/interfaces/api/solver/pose/I2Dto3DTransformDecomposerValidation.h +++ b/interfaces/api/solver/pose/I2Dto3DTransformDecomposerValidation.h @@ -16,7 +16,7 @@ namespace pose { * @brief Validates if a transform decomposition is correct. * UUID: ee990fc4-ec74-4365-8fa8-b2c94845fde6 */ -class [[xpcf::clientUUID("21d1a9c4-c018-4b9a-99b8-68055b82c869")]] [[xpcf::serverUUID("447acd52-ad9f-4338-aff1-f61084bd0621")]] I2Dto3DTransformDecomposerValidation : +class XPCF_CLIENTUUID("21d1a9c4-c018-4b9a-99b8-68055b82c869") XPCF_SERVERUUID("447acd52-ad9f-4338-aff1-f61084bd0621") I2Dto3DTransformDecomposerValidation : virtual public org::bcom::xpcf::IComponentIntrospect { public: /// @brief I2Dto3DTransformDecomposerValidation default constructor. diff --git a/interfaces/api/solver/pose/I3D3DCorrespondencesFinder.h b/interfaces/api/solver/pose/I3D3DCorrespondencesFinder.h index 7796074b..13588449 100644 --- a/interfaces/api/solver/pose/I3D3DCorrespondencesFinder.h +++ b/interfaces/api/solver/pose/I3D3DCorrespondencesFinder.h @@ -35,7 +35,7 @@ namespace pose { * @brief Finds the 3D-3D correspondences from feature matches of two keyframes. * UUID: 90068876-655a-4d86-adfc-96a519041ab3 */ -class [[xpcf::clientUUID("0fe355bf-17f5-426f-af10-f630331d7476")]] [[xpcf::serverUUID("c758fd66-bd9e-4aae-9580-008afe3a37c0")]] I3D3DCorrespondencesFinder : +class XPCF_CLIENTUUID("0fe355bf-17f5-426f-af10-f630331d7476") XPCF_SERVERUUID("c758fd66-bd9e-4aae-9580-008afe3a37c0") I3D3DCorrespondencesFinder : virtual public org::bcom::xpcf::IComponentIntrospect { public: /// @brief I3D3DCorrespondencesFinder default constructor. diff --git a/interfaces/api/solver/pose/I3DTransformFinderFrom2D2D.h b/interfaces/api/solver/pose/I3DTransformFinderFrom2D2D.h index 6815f844..f25d18b6 100644 --- a/interfaces/api/solver/pose/I3DTransformFinderFrom2D2D.h +++ b/interfaces/api/solver/pose/I3DTransformFinderFrom2D2D.h @@ -35,7 +35,7 @@ namespace pose { * @brief Finds the 3D transform between two cameras knowing the keypoints that match between them. * UUID: 6063a606-9d30-11e8-98d0-529269fb1459 */ -class [[xpcf::clientUUID("62f0a994-3ad4-4322-8059-7513153d074a")]] [[xpcf::serverUUID("84c693c0-3301-453f-9fca-f0e6208b89bc")]] I3DTransformFinderFrom2D2D : +class XPCF_CLIENTUUID("62f0a994-3ad4-4322-8059-7513153d074a") XPCF_SERVERUUID("84c693c0-3301-453f-9fca-f0e6208b89bc") I3DTransformFinderFrom2D2D : virtual public org::bcom::xpcf::IComponentIntrospect { public: ///@brief I3DTransformFinderFrom2D2D default constructor. diff --git a/interfaces/api/solver/pose/I3DTransformFinderFrom2D3D.h b/interfaces/api/solver/pose/I3DTransformFinderFrom2D3D.h index d5c421e8..8bed2b3b 100644 --- a/interfaces/api/solver/pose/I3DTransformFinderFrom2D3D.h +++ b/interfaces/api/solver/pose/I3DTransformFinderFrom2D3D.h @@ -34,7 +34,7 @@ namespace pose { * @brief Finds the 3D transform of 2D-3D points correspondences. * UUID: 77281cda-47c2-4bb7-bde6-5b0d02e75dae */ -class [[xpcf::clientUUID("201fb9e7-9452-42e2-a587-9e9b3e49c889")]] [[xpcf::serverUUID("cf5a7828-f6e1-482a-bb0c-b8e44ac9a22d")]] I3DTransformFinderFrom2D3D : +class XPCF_CLIENTUUID("201fb9e7-9452-42e2-a587-9e9b3e49c889") XPCF_SERVERUUID("cf5a7828-f6e1-482a-bb0c-b8e44ac9a22d") I3DTransformFinderFrom2D3D : virtual public org::bcom::xpcf::IComponentIntrospect { public: ///@brief I3DTransformFinderFrom2D3D default constructor. diff --git a/interfaces/api/solver/pose/I3DTransformFinderFrom3D3D.h b/interfaces/api/solver/pose/I3DTransformFinderFrom3D3D.h index 9371bfd1..57a1ce42 100644 --- a/interfaces/api/solver/pose/I3DTransformFinderFrom3D3D.h +++ b/interfaces/api/solver/pose/I3DTransformFinderFrom3D3D.h @@ -30,7 +30,7 @@ namespace pose { * @class I3DTransformFinderFrom3D3D * @brief Finds the 3D transform of a depth sensor from a point cloud captured by this sensor and a point cloud representing a geometric knowledge of the real world. */ -class [[xpcf::clientUUID("894e87bc-c3a1-4728-844f-a8c565d06522")]] [[xpcf::serverUUID("51f343ee-9231-4a7a-af03-fe90e857d676")]] I3DTransformFinderFrom3D3D : +class XPCF_CLIENTUUID("894e87bc-c3a1-4728-844f-a8c565d06522") XPCF_SERVERUUID("51f343ee-9231-4a7a-af03-fe90e857d676") I3DTransformFinderFrom3D3D : virtual public org::bcom::xpcf::IComponentIntrospect { public: ///@brief I3DTransformFinderFrom3D3D default constructor. diff --git a/interfaces/api/solver/pose/I3DTransformSACFinderFrom2D3D.h b/interfaces/api/solver/pose/I3DTransformSACFinderFrom2D3D.h index 24ecb634..fc39bc3c 100644 --- a/interfaces/api/solver/pose/I3DTransformSACFinderFrom2D3D.h +++ b/interfaces/api/solver/pose/I3DTransformSACFinderFrom2D3D.h @@ -34,7 +34,7 @@ namespace pose { * @brief Finds the 3D transform of 2D-3D points correspondences with a SAmple Consensus. * UUID: 8dd889c5-e8e6-4b3b-92e4-34cf7442f272 */ -class [[xpcf::clientUUID("502c323f-1063-4efc-8ac6-c45469632546")]] [[xpcf::serverUUID("beb7849c-b08d-4895-838a-4c6d1fa9d757")]] I3DTransformSACFinderFrom2D3D : +class XPCF_CLIENTUUID("502c323f-1063-4efc-8ac6-c45469632546") XPCF_SERVERUUID("beb7849c-b08d-4895-838a-4c6d1fa9d757") I3DTransformSACFinderFrom2D3D : virtual public org::bcom::xpcf::IComponentIntrospect { public: ///@brief I3DTransformSACFinderFrom2D3D default constructor. diff --git a/interfaces/api/solver/pose/I3DTransformSACFinderFrom3D3D.h b/interfaces/api/solver/pose/I3DTransformSACFinderFrom3D3D.h index e4977c61..3dfe0081 100644 --- a/interfaces/api/solver/pose/I3DTransformSACFinderFrom3D3D.h +++ b/interfaces/api/solver/pose/I3DTransformSACFinderFrom3D3D.h @@ -35,7 +35,7 @@ namespace pose { * @brief Finds the 3D transform of 3D-3D points correspondences with a SAmple Consensus. * UUID: 940bddba-da70-4a6e-a327-890c1e61386d */ -class [[xpcf::clientUUID("c5d93531-de0c-4424-b48f-00709822dd4a")]] [[xpcf::serverUUID("22e36805-4596-4440-b87d-18114e73ff6d")]] I3DTransformSACFinderFrom3D3D : +class XPCF_CLIENTUUID("c5d93531-de0c-4424-b48f-00709822dd4a") XPCF_SERVERUUID("22e36805-4596-4440-b87d-18114e73ff6d") I3DTransformSACFinderFrom3D3D : virtual public org::bcom::xpcf::IComponentIntrospect { public: ///@brief I3DTransformSACFinderFrom3D3D default constructor. diff --git a/interfaces/api/solver/pose/IHomographyValidation.h b/interfaces/api/solver/pose/IHomographyValidation.h index 937201da..ae3b48e7 100644 --- a/interfaces/api/solver/pose/IHomographyValidation.h +++ b/interfaces/api/solver/pose/IHomographyValidation.h @@ -32,7 +32,7 @@ namespace pose { * @brief Tests if a homography is valid. * UUID: e95e8f70-dd32-11e7-9296-cec278b6b50a */ -class [[xpcf::clientUUID("55221e5e-67cc-487c-a277-1d56e3637e42")]] [[xpcf::serverUUID("ca9cda6e-6cf1-495d-a51d-da1286f4f3d3")]] IHomographyValidation : +class XPCF_CLIENTUUID("55221e5e-67cc-487c-a277-1d56e3637e42") XPCF_SERVERUUID("ca9cda6e-6cf1-495d-a51d-da1286f4f3d3") IHomographyValidation : virtual public org::bcom::xpcf::IComponentIntrospect { public: /// @brief IHomographyValidation default constructor diff --git a/interfaces/api/solver/pose/IMultiTrackablesPose.h b/interfaces/api/solver/pose/IMultiTrackablesPose.h index e92047b5..c4c856c3 100644 --- a/interfaces/api/solver/pose/IMultiTrackablesPose.h +++ b/interfaces/api/solver/pose/IMultiTrackablesPose.h @@ -34,7 +34,7 @@ namespace pose { * @brief Estimate camera pose based on a set of given trackables. * UUID: f22cede0-e638-403f-9dfc-d2c1bd15cf83 */ -class [[xpcf::clientUUID("cf2959b3-cc73-46fa-8082-0809a3a2dcd3")]] [[xpcf::serverUUID("85daed2c-bd7d-4636-8321-b5f22e22ae11")]] IMultiTrackablesPose : +class XPCF_CLIENTUUID("cf2959b3-cc73-46fa-8082-0809a3a2dcd3") XPCF_SERVERUUID("85daed2c-bd7d-4636-8321-b5f22e22ae11") IMultiTrackablesPose : virtual public org::bcom::xpcf::IComponentIntrospect { public: ///@brief IMultiTrackablesPose default constructor. diff --git a/interfaces/api/solver/pose/ITrackablePose.h b/interfaces/api/solver/pose/ITrackablePose.h index a562978c..d443f0d4 100644 --- a/interfaces/api/solver/pose/ITrackablePose.h +++ b/interfaces/api/solver/pose/ITrackablePose.h @@ -34,7 +34,7 @@ namespace pose { * @brief Estimate camera pose based on a given trackable. * UUID: d5247968-b74e-4afb-9abd-546021441ad4 */ -class [[xpcf::clientUUID("ad79b898-f2b0-446f-835e-7daf3458fe50")]] [[xpcf::serverUUID("cd7858b0-0bfa-4ece-b16a-3e02fa309495")]] ITrackablePose : +class XPCF_CLIENTUUID("ad79b898-f2b0-446f-835e-7daf3458fe50") XPCF_SERVERUUID("cd7858b0-0bfa-4ece-b16a-3e02fa309495") ITrackablePose : virtual public org::bcom::xpcf::IComponentIntrospect { public: ///@brief ITrackablePose default constructor. diff --git a/interfaces/api/storage/IMapManager.h b/interfaces/api/storage/IMapManager.h index 35e28672..c06f17a2 100644 --- a/interfaces/api/storage/IMapManager.h +++ b/interfaces/api/storage/IMapManager.h @@ -43,7 +43,7 @@ namespace storage { * UUID: 90075c1b-915b-469d-b92d-41c5d575bf15 */ -class [[xpcf::clientUUID("9c68f766-3b6f-427f-91d3-1e5126d27326")]] [[xpcf::serverUUID("41cbf117-f6cd-4efa-a7d9-a3c92b3656e4")]] IMapManager : +class XPCF_CLIENTUUID("9c68f766-3b6f-427f-91d3-1e5126d27326") XPCF_SERVERUUID("41cbf117-f6cd-4efa-a7d9-a3c92b3656e4") IMapManager : virtual public org::bcom::xpcf::IComponentIntrospect { public: /// @brief IMapManager default constructor diff --git a/interfaces/api/tracking/IOpticalFlowEstimator.h b/interfaces/api/tracking/IOpticalFlowEstimator.h index 02af6c4f..6bdf2e45 100644 --- a/interfaces/api/tracking/IOpticalFlowEstimator.h +++ b/interfaces/api/tracking/IOpticalFlowEstimator.h @@ -35,7 +35,7 @@ namespace tracking { * This interface is defined to implement components to estimate the optical flow between two images. */ -class [[xpcf::clientUUID("acc7cbc7-ea8d-4034-a568-363d9b820eed")]] [[xpcf::serverUUID("af06b587-5be2-4d1a-87ed-ad900d47fe82")]] IOpticalFlowEstimator : +class XPCF_CLIENTUUID("acc7cbc7-ea8d-4034-a568-363d9b820eed") XPCF_SERVERUUID("af06b587-5be2-4d1a-87ed-ad900d47fe82") IOpticalFlowEstimator : virtual public org::bcom::xpcf::IComponentIntrospect { public: /// @brief IOpticalFlow default constructor diff --git a/interfaces/base/features/ADescriptorMatcher.h b/interfaces/base/features/ADescriptorMatcher.h index b787a729..19691c4e 100644 --- a/interfaces/base/features/ADescriptorMatcher.h +++ b/interfaces/base/features/ADescriptorMatcher.h @@ -43,9 +43,9 @@ class XPCF_IGNORE SOLARFRAMEWORK_API ADescriptorMatcher : public org::bcom::xpcf /// @param[in] descriptors2 The second set of descriptors organized in a dedicated buffer structure. /// @param[out] matches A vector of matches representing pairs of indices relatively to the first and second set of descriptors. /// @return FrameworkReturnCode::_SUCCESS if matching succeed, else FrameworkReturnCode::_ERROR_ - virtual FrameworkReturnCode match(const SRef descriptors1, - const SRef descriptors2, - std::vector & matches) override + virtual FrameworkReturnCode match(const SRef /*descriptors1*/, + const SRef /*descriptors2*/, + std::vector & /*matches*/) override { return FrameworkReturnCode::_NOT_IMPLEMENTED; } /// @brief Match two sets of descriptors together. The second set is organized in a vector of descriptors buffer and can be used if the descriptors have been extracted on subsets of an image. diff --git a/interfaces/base/features/ADescriptorMatcherGeometric.h b/interfaces/base/features/ADescriptorMatcherGeometric.h index c87614dc..3981c3e6 100644 --- a/interfaces/base/features/ADescriptorMatcherGeometric.h +++ b/interfaces/base/features/ADescriptorMatcherGeometric.h @@ -50,17 +50,17 @@ class XPCF_IGNORE SOLARFRAMEWORK_API ADescriptorMatcherGeometric : public org::b /// @param[in] mask1 The indices of descriptors in the first frame are used for matching to the second frame. If it is empty then all will be used. /// @param[in] mask2 The indices of descriptors in the second frame are used for matching to the first frame. If it is empty then all will be used. /// @return FrameworkReturnCode::_SUCCESS if matching succeed, else FrameworkReturnCode::_ERROR_ - virtual FrameworkReturnCode match(const SRef descriptors1, - const SRef descriptors2, - const std::vector &undistortedKeypoints1, - const std::vector &undistortedKeypoints2, - const SolAR::datastructure::Transform3Df& pose1, - const SolAR::datastructure::Transform3Df& pose2, - const SolAR::datastructure::CameraParameters & camParams1, - const SolAR::datastructure::CameraParameters & camParams2, - std::vector & matches, - const std::vector& mask1 = {}, - const std::vector& mask2 = {}) override + virtual FrameworkReturnCode match(const SRef /* descriptors1 */, + const SRef /* descriptors2 */, + const std::vector & /* undistortedKeypoints1, */, + const std::vector & /* undistortedKeypoints2 */, + const SolAR::datastructure::Transform3Df& /* pose1, */, + const SolAR::datastructure::Transform3Df& /* pose2 */, + const SolAR::datastructure::CameraParameters & /* camParams1, */, + const SolAR::datastructure::CameraParameters & /* camParams2 */, + std::vector & /* matches */, + const std::vector& /* mask1 */, + const std::vector& /* mask2 */) override { return FrameworkReturnCode::_NOT_IMPLEMENTED; } /// @brief Match two sets of descriptors from two frames based on epipolar constraint. diff --git a/interfaces/base/features/ADescriptorMatcherRegion.h b/interfaces/base/features/ADescriptorMatcherRegion.h index 4258d2ad..a160f792 100644 --- a/interfaces/base/features/ADescriptorMatcherRegion.h +++ b/interfaces/base/features/ADescriptorMatcherRegion.h @@ -46,13 +46,13 @@ class XPCF_IGNORE SOLARFRAMEWORK_API ADescriptorMatcherRegion : public org::bcom /// @param[in] radius the radius of search region around each keypoint of the first set. /// @param[in] matchingDistanceMax the maximum distance to valid a match. /// @return FrameworkReturnCode::_SUCCESS if matching succeed, else FrameworkReturnCode::_ERROR_ - virtual FrameworkReturnCode match(const SRef descriptors1, - const SRef descriptors2, - const std::vector & points2D1, - const std::vector & points2D2, - std::vector &matches, - const float radius = -1.f, - const float matchingDistanceMax = -1.f) override + virtual FrameworkReturnCode match(const SRef /*descriptors1*/, + const SRef /*descriptors2*/, + const std::vector & /*points2D1*/, + const std::vector & /*points2D2*/, + std::vector &/*matches*/, + const float /*radius = -1.f */, + const float /*matchingDistanceMax = -1.f */) override { return FrameworkReturnCode::_NOT_IMPLEMENTED;} /// @brief Match each descriptor input to descriptors of a frame in a region. The searching space is a circle which is defined by a 2D center and a radius diff --git a/interfaces/base/features/ADescriptorMatcherStereo.h b/interfaces/base/features/ADescriptorMatcherStereo.h index eb33996c..be649462 100644 --- a/interfaces/base/features/ADescriptorMatcherStereo.h +++ b/interfaces/base/features/ADescriptorMatcherStereo.h @@ -45,12 +45,12 @@ class XPCF_IGNORE SOLARFRAMEWORK_API ADescriptorMatcherStereo : public org::bcom /// @param[in] type Stereo type (horizontal or vertical). /// @param[out] matches A vector of matches representing pairs of indices relatively to the first and second set of descriptors. /// @return FrameworkReturnCode::_SUCCESS if matching succeed, else FrameworkReturnCode::_ERROR_ - virtual FrameworkReturnCode match(const SRef& descriptors1, - const SRef& descriptors2, - const std::vector& undistortedKeypoints1, - const std::vector& undistortedKeypoints2, - SolAR::datastructure::StereoType type, - std::vector &matches) override + virtual FrameworkReturnCode match(const SRef& /*descriptors1*/, + const SRef& /*descriptors2*/, + const std::vector& /*undistortedKeypoints1*/, + const std::vector& /*undistortedKeypoints2*/, + SolAR::datastructure::StereoType /*type*/, + std::vector &/*matches*/) override { return FrameworkReturnCode::_NOT_IMPLEMENTED; } /// @brief Match two sets of descriptors from stereo images. diff --git a/interfaces/base/geom/A2DPointsRectification.h b/interfaces/base/geom/A2DPointsRectification.h index a31316c4..60233e45 100644 --- a/interfaces/base/geom/A2DPointsRectification.h +++ b/interfaces/base/geom/A2DPointsRectification.h @@ -43,10 +43,10 @@ class XPCF_IGNORE SOLARFRAMEWORK_API A2DPointsRectification : public org::bcom:: /// @param[in] rectParams The rectification parameters of camera /// @param[out] rectifiedPoints2D The rectified 2D points /// @return FrameworkReturnCode::_SUCCESS if rectifying succeed, else FrameworkReturnCode::_ERROR_ - virtual FrameworkReturnCode rectify(const std::vector& points2D, - const SolAR::datastructure::CameraParameters& camParams, - const SolAR::datastructure::RectificationParameters& rectParams, - std::vector& rectifiedPoints2D) override + virtual FrameworkReturnCode rectify(const std::vector& /*points2D*/, + const SolAR::datastructure::CameraParameters& /*camParams*/, + const SolAR::datastructure::RectificationParameters& /*rectParams*/, + std::vector& /*rectifiedPoints2D*/) override { return FrameworkReturnCode::_NOT_IMPLEMENTED; } /// @brief Rectify 2D keypoints diff --git a/interfaces/base/geom/AReprojectionStereo.h b/interfaces/base/geom/AReprojectionStereo.h index 50e8aa9a..ed3f418f 100644 --- a/interfaces/base/geom/AReprojectionStereo.h +++ b/interfaces/base/geom/AReprojectionStereo.h @@ -42,9 +42,9 @@ class XPCF_IGNORE SOLARFRAMEWORK_API AReprojectionStereo : public org::bcom::xpc /// @param[in] rectParams The rectification parameters. /// @param[out] unrectifiedKeypoints The unrectified keypoints for estimating depth information. /// @return FrameworkReturnCode::_SUCCESS if reprojecting succeed, else FrameworkReturnCode::_ERROR_ - virtual FrameworkReturnCode reprojectToUnrectification(const std::vector& rectifiedKeypoints, - const SolAR::datastructure::RectificationParameters& rectParams, - std::vector& unrectifiedKeypoints) override + virtual FrameworkReturnCode reprojectToUnrectification(const std::vector& /*rectifiedKeypoints*/, + const SolAR::datastructure::RectificationParameters& /*rectParams*/, + std::vector& /*unrectifiedKeypoints*/) override { return FrameworkReturnCode::_NOT_IMPLEMENTED; } /// @brief Reproject 2D keypoints with depths to 3D cloud points in the world coordinate system @@ -54,11 +54,11 @@ class XPCF_IGNORE SOLARFRAMEWORK_API AReprojectionStereo : public org::bcom::xpc /// @param[in] intrinsicParams The intrinsic parameters of the camera. /// @param[out] cloudPoints The output cloud points. /// @return FrameworkReturnCode::_SUCCESS if reprojecting succeed, else FrameworkReturnCode::_ERROR_ - virtual FrameworkReturnCode reprojectToCloudPoints(const std::vector& undistortedKeypoints, - const SRef descriptors, - const SolAR::datastructure::Transform3Df& pose, - const SolAR::datastructure::CamCalibration& intrinsicParams, - std::vector>& cloudPoints) override + virtual FrameworkReturnCode reprojectToCloudPoints(const std::vector& /*undistortedKeypoints*/, + const SRef /*descriptors*/, + const SolAR::datastructure::Transform3Df& /*pose*/, + const SolAR::datastructure::CamCalibration& /*intrinsicParams*/, + std::vector>& /*cloudPoints*/) override { return FrameworkReturnCode::_NOT_IMPLEMENTED; } /// @brief Reproject 2D keypoints with depths of a frame to 3D cloud points in the world coordinate system diff --git a/interfaces/base/pipeline/AMappingPipeline.h b/interfaces/base/pipeline/AMappingPipeline.h index a65f8871..026a29f5 100644 --- a/interfaces/base/pipeline/AMappingPipeline.h +++ b/interfaces/base/pipeline/AMappingPipeline.h @@ -40,29 +40,29 @@ class XPCF_IGNORE SOLARFRAMEWORK_API AMappingPipeline : public org::bcom::xpcf:: /// @brief Set the camera parameters /// @param[in] cameraParams: the camera parameters (its resolution and its focal) /// @return FrameworkReturnCode::_SUCCESS if the camera parameters are correctly set, else FrameworkReturnCode::_ERROR_ - virtual FrameworkReturnCode setCameraParameters(const SolAR::datastructure::CameraParameters & cameraParams) override + virtual FrameworkReturnCode setCameraParameters(const SolAR::datastructure::CameraParameters & /* cameraParams */) override { return FrameworkReturnCode::_NOT_IMPLEMENTED; } /// @brief Set the camera parameters (use for stereo camera) /// @param[in] cameraParams1 the camera parameters of the first camera /// @param[in] cameraParams2 the camera parameters of the second camera /// @return FrameworkReturnCode::_SUCCESS if the camera parameters are correctly set, else FrameworkReturnCode::_ERROR_ - virtual FrameworkReturnCode setCameraParameters(const SolAR::datastructure::CameraParameters & cameraParams1, - const SolAR::datastructure::CameraParameters & cameraParams2) override + virtual FrameworkReturnCode setCameraParameters(const SolAR::datastructure::CameraParameters & /* cameraParams1 */, + const SolAR::datastructure::CameraParameters & /* cameraParams2 */) override { return FrameworkReturnCode::_NOT_IMPLEMENTED; } /// @brief Set the rectification parameters (use for stereo camera) /// @param[in] rectCam1 the rectification parameters of the first camera /// @param[in] rectCam2 the rectification parameters of the second camera /// @return FrameworkReturnCode::_SUCCESS if the rectification parameters are correctly set, else FrameworkReturnCode::_ERROR_ - virtual FrameworkReturnCode setRectificationParameters(const SolAR::datastructure::RectificationParameters & rectCam1, - const SolAR::datastructure::RectificationParameters & rectCam2) override + virtual FrameworkReturnCode setRectificationParameters(const SolAR::datastructure::RectificationParameters & /* rectCam1 */, + const SolAR::datastructure::RectificationParameters & /* rectCam2 */) override { return FrameworkReturnCode::_NOT_IMPLEMENTED; } /// @brief Set the 3D transformation from SolAR to world spaces /// @param[in] transform the transformation matrix from SolAR to World /// @return FrameworkReturnCode::_SUCCESS if the transform is correctly set, else FrameworkReturnCode::_ERROR_ - virtual FrameworkReturnCode set3DTransformSolARToWorld(const SolAR::datastructure::Transform3Df & transform) override + virtual FrameworkReturnCode set3DTransformSolARToWorld(const SolAR::datastructure::Transform3Df & /* transform*/) override { return FrameworkReturnCode::_NOT_IMPLEMENTED; } /// @brief Request to the mapping pipeline to process a new image/pose @@ -73,12 +73,12 @@ class XPCF_IGNORE SOLARFRAMEWORK_API AMappingPipeline : public org::bcom::xpcf:: /// @param[out] updatedTransform the refined transformation by a loop closure detection /// @param[out] status the current status of the mapping pipeline /// @return FrameworkReturnCode::_SUCCESS if the data are ready to be processed, else FrameworkReturnCode::_ERROR_ - virtual FrameworkReturnCode mappingProcessRequest(const std::vector> & images, - const std::vector & poses, - bool fixedPose, - const SolAR::datastructure::Transform3Df & transform, - SolAR::datastructure::Transform3Df & updatedTransform, - SolAR::api::pipeline::MappingStatus & status) override + virtual FrameworkReturnCode mappingProcessRequest(const std::vector> & /* images */, + const std::vector & /*poses*/, + bool /*fixedPose*/, + const SolAR::datastructure::Transform3Df & /*transform*/, + SolAR::datastructure::Transform3Df & /*updatedTransform*/, + SolAR::api::pipeline::MappingStatus & /*status*/) override { return FrameworkReturnCode::_NOT_IMPLEMENTED; } /// @brief Request to the mapping pipeline to process a new image/pose @@ -110,8 +110,8 @@ class XPCF_IGNORE SOLARFRAMEWORK_API AMappingPipeline : public org::bcom::xpcf:: /// @param[out] outputPointClouds: pipeline current point clouds /// @param[out] keyframePoses: pipeline current keyframe poses /// @return FrameworkReturnCode::_SUCCESS if data are available, else FrameworkReturnCode::_ERROR_ - virtual FrameworkReturnCode getDataForVisualization(std::vector> & outputPointClouds, - std::vector & keyframePoses) const override + virtual FrameworkReturnCode getDataForVisualization(std::vector> & /*outputPointClouds*/, + std::vector & /*keyframePoses*/) const override { return FrameworkReturnCode::_NOT_IMPLEMENTED; } }; } diff --git a/interfaces/datastructure/BufferInternal.hpp b/interfaces/datastructure/BufferInternal.hpp index 415fe1f1..72cea0ea 100644 --- a/interfaces/datastructure/BufferInternal.hpp +++ b/interfaces/datastructure/BufferInternal.hpp @@ -81,7 +81,7 @@ class BufferInternal { private: friend class boost::serialization::access; template - void serialize(Archive &ar, ATTRIBUTE(maybe_unused) const unsigned int version) { + void serialize(Archive &ar, const unsigned int /* version */) { ar & m_storageData; ar & m_bufferSize; } diff --git a/interfaces/datastructure/CameraDefinitions.h b/interfaces/datastructure/CameraDefinitions.h index 6157a34c..63d4fc43 100644 --- a/interfaces/datastructure/CameraDefinitions.h +++ b/interfaces/datastructure/CameraDefinitions.h @@ -148,7 +148,7 @@ namespace boost { namespace serialization { template inline void serialize(Archive & ar, SolAR::datastructure::CameraParameters & parameters, - ATTRIBUTE(maybe_unused) const unsigned int version) + const unsigned int /* version */) { ar & parameters.name; ar & parameters.id; @@ -161,7 +161,7 @@ inline void serialize(Archive & ar, template inline void serialize(Archive & ar, SolAR::datastructure::RectificationParameters & parameters, - ATTRIBUTE(maybe_unused) const unsigned int version) + const unsigned int /* version */) { ar & parameters.baseline; ar & parameters.type; @@ -172,7 +172,7 @@ inline void serialize(Archive & ar, template inline void serialize(Archive & ar, SolAR::datastructure::CameraRigParameters & parameters, - ATTRIBUTE(maybe_unused) const unsigned int version) + const unsigned int /* version */) { ar & parameters.cameraParams; ar & parameters.rectificationParams; diff --git a/interfaces/datastructure/DescriptorBuffer.h b/interfaces/datastructure/DescriptorBuffer.h index f73ae56b..c723d525 100644 --- a/interfaces/datastructure/DescriptorBuffer.h +++ b/interfaces/datastructure/DescriptorBuffer.h @@ -162,7 +162,7 @@ class SOLARFRAMEWORK_API DescriptorBufferIterator { } inline DescriptorView operator *(); - bool operator !=(ATTRIBUTE(maybe_unused) const DescriptorBufferIterator & desc) { + bool operator !=(const DescriptorBufferIterator & /* desc */) { return (m_index != m_nbDescriptors); } diff --git a/interfaces/datastructure/GeometryDefinitions.h b/interfaces/datastructure/GeometryDefinitions.h index 14b79bc3..e8c6f03b 100644 --- a/interfaces/datastructure/GeometryDefinitions.h +++ b/interfaces/datastructure/GeometryDefinitions.h @@ -48,7 +48,7 @@ class Point2Df : public Vector { private: friend class boost::serialization::access; template - void serialize(Archive &ar, ATTRIBUTE(maybe_unused) const unsigned int version){ + void serialize(Archive &ar, const unsigned int /* version */){ ar & boost::serialization::make_array(this->data(), 2); } }; @@ -79,7 +79,7 @@ class Point3Df : public Vector { private: friend class boost::serialization::access; template - void serialize(Archive &ar, ATTRIBUTE(maybe_unused) const unsigned int version){ + void serialize(Archive &ar, const unsigned int /* version */){ ar & boost::serialization::make_array(this->data(), 3); } }; @@ -135,7 +135,7 @@ class Point3Di : public Vector { private: friend class boost::serialization::access; template - void serialize(Archive &ar, const unsigned int version){ + void serialize(Archive &ar, const unsigned int /* version */){ ar & boost::serialization::make_array(this->data(), 3); } }; @@ -157,7 +157,7 @@ class Edge2Df { private: friend class boost::serialization::access; template - void serialize(Archive &ar, const unsigned int version){ + void serialize(Archive &ar, const unsigned int /* version */){ ar & p1; ar & p2; } @@ -205,7 +205,7 @@ class BBox3Df { private: friend class boost::serialization::access; template - void serialize(Archive &ar, ATTRIBUTE(maybe_unused) const unsigned int version){ + void serialize(Archive &ar, const unsigned int /* version */){ ar & corner; ar & width; ar & height; @@ -280,7 +280,7 @@ namespace boost { namespace serialization { template inline void serialize(Archive & ar, SolAR::datastructure::Sizef & size, - ATTRIBUTE(maybe_unused) const unsigned int version) + const unsigned int /* version */) { ar & size.width; ar & size.height; @@ -289,7 +289,7 @@ inline void serialize(Archive & ar, template inline void serialize(Archive & ar, SolAR::datastructure::Sizei & size, - ATTRIBUTE(maybe_unused) const unsigned int version) + const unsigned int /* version */) { ar & size.width; ar & size.height; @@ -298,7 +298,7 @@ inline void serialize(Archive & ar, template inline void serialize(Archive & ar, SolAR::datastructure::Rectanglei & rect, - ATTRIBUTE(maybe_unused) const unsigned int version) + const unsigned int /* version */) { ar & rect.startX; ar & rect.startY; diff --git a/interfaces/datastructure/MathDefinitions.h b/interfaces/datastructure/MathDefinitions.h index 122a35bd..ecaab055 100644 --- a/interfaces/datastructure/MathDefinitions.h +++ b/interfaces/datastructure/MathDefinitions.h @@ -242,7 +242,7 @@ static Quaternionf quaternionAverage(const std::vector& quaternions * @param[in] transforms list of transform3D * @return average transform3D */ -static Transform3Df transform3DAverage(const std::vector& transforms) { + [[maybe_unused]] static Transform3Df transform3DAverage(const std::vector& transforms) { if (transforms.size() == 0) return Transform3Df(Maths::Matrix4f::Zero()); else if (transforms.size() == 1) @@ -276,7 +276,7 @@ template< class Archive, int MaxCols_> inline void serialize(Archive & ar, Eigen::Matrix & matrix, - ATTRIBUTE(maybe_unused) const unsigned int version) + const unsigned int /* version */) { int rows = matrix.rows(); int cols = matrix.cols(); diff --git a/interfaces/datastructure/PointCloud.h b/interfaces/datastructure/PointCloud.h index 236ce12a..4034c25c 100644 --- a/interfaces/datastructure/PointCloud.h +++ b/interfaces/datastructure/PointCloud.h @@ -42,8 +42,8 @@ class SOLARFRAMEWORK_API PointCloud : public Lockable { /// @brief PointCloud constructor. /// PointCloud() { m_id = 0; }; - PointCloud(const PointCloud& other): m_id(other.m_id), m_descriptorType(other.m_descriptorType), m_pointCloud(other.m_pointCloud){}; - PointCloud& operator=(const PointCloud& other) { return *this; }; + PointCloud(const PointCloud& other): m_pointCloud(other.m_pointCloud), m_descriptorType(other.m_descriptorType), m_id(other.m_id) {}; + PointCloud& operator=(const PointCloud& /* other */) { return *this; }; /// /// @brief ~PointCloud diff --git a/src/base/geom/A2DPointsRectification.cpp b/src/base/geom/A2DPointsRectification.cpp index 4d9718e8..2e8cc9e6 100644 --- a/src/base/geom/A2DPointsRectification.cpp +++ b/src/base/geom/A2DPointsRectification.cpp @@ -38,7 +38,7 @@ FrameworkReturnCode A2DPointsRectification::rectify(const std::vectorsecond); - return FrameworkReturnCode::_SUCCESS; + return FrameworkReturnCode::_SUCCESS; } FrameworkReturnCode CameraParametersCollection::suppressCameraParameters(const uint32_t id) @@ -139,7 +139,7 @@ int CameraParametersCollection::getNbCameraParameters() const } template -void CameraParametersCollection::serialize(Archive &ar, ATTRIBUTE(maybe_unused) const unsigned int version) +void CameraParametersCollection::serialize(Archive &ar, const unsigned int /* version */) { ar & m_id; ar & m_cameraParameters; diff --git a/src/datastructure/CloudPoint.cpp b/src/datastructure/CloudPoint.cpp index a7ef925e..5647160b 100644 --- a/src/datastructure/CloudPoint.cpp +++ b/src/datastructure/CloudPoint.cpp @@ -38,19 +38,19 @@ CloudPoint::CloudPoint(float x, float y, float z, float r, float g, float b, flo } CloudPoint::CloudPoint(float x, float y, float z, float r, float g, float b, double reproj_error, const std::map& visibility) : - Point3Df(x, y, z), m_rgb(r, g, b), m_reproj_error(reproj_error), m_visibility(visibility) + Point3Df(x, y, z), m_visibility(visibility), m_rgb(r, g, b), m_reproj_error(reproj_error) { m_cloudPointSupportedTypes = CloudPointType::Color | CloudPointType::ViewDirection | CloudPointType::Visibility; } CloudPoint::CloudPoint(float x, float y, float z, float r, float g, float b, float nx, float ny, float nz, double reproj_error, const std::map& visibility) : - Point3Df(x, y, z), m_rgb(r, g, b), m_viewDirection(nx, ny, nz), m_reproj_error(reproj_error), m_visibility(visibility) + Point3Df(x, y, z), m_visibility(visibility), m_rgb(r, g, b), m_viewDirection(nx, ny, nz), m_reproj_error(reproj_error) { m_cloudPointSupportedTypes = CloudPointType::Color | CloudPointType::ViewDirection | CloudPointType::ReprojectionError | CloudPointType::Visibility ; } CloudPoint::CloudPoint(float x, float y, float z, float r, float g, float b, double reproj_error, const std::map& visibility, SRef descriptor) : - Point3Df(x, y, z), m_rgb(r, g, b), m_reproj_error(reproj_error), m_visibility(visibility), m_descriptor(descriptor) + Point3Df(x, y, z), m_descriptor(descriptor), m_visibility(visibility), m_rgb(r, g, b), m_reproj_error(reproj_error) { m_cloudPointSupportedTypes = CloudPointType::Color | CloudPointType::ReprojectionError | CloudPointType::Visibility; if (descriptor != nullptr) @@ -58,7 +58,7 @@ CloudPoint::CloudPoint(float x, float y, float z, float r, float g, float b, dou } CloudPoint::CloudPoint(float x, float y, float z, float r, float g, float b, float nx, float ny, float nz, double reproj_error, const std::map& visibility, SRef descriptor) : - Point3Df(x, y, z), m_rgb(r, g, b), m_viewDirection(nx, ny, nz), m_reproj_error(reproj_error), m_visibility(visibility), m_descriptor(descriptor) + Point3Df(x, y, z), m_descriptor(descriptor), m_visibility(visibility), m_rgb(r, g, b), m_viewDirection(nx, ny, nz), m_reproj_error(reproj_error) { m_cloudPointSupportedTypes = CloudPointType::Color | CloudPointType::ViewDirection | CloudPointType::ReprojectionError | CloudPointType::Visibility; if (descriptor != nullptr) @@ -163,7 +163,7 @@ bool CloudPoint::removeVisibility(const uint32_t& keyframe_id) } template -void CloudPoint::serialize(Archive &ar, ATTRIBUTE(maybe_unused) const unsigned int version) +void CloudPoint::serialize(Archive &ar, const unsigned int /* version */) { ar.template register_type(); ar & m_cloudPointSupportedTypes; diff --git a/src/datastructure/CoordinateSystem.cpp b/src/datastructure/CoordinateSystem.cpp index 1c2f53cb..f31e5dc8 100644 --- a/src/datastructure/CoordinateSystem.cpp +++ b/src/datastructure/CoordinateSystem.cpp @@ -65,7 +65,7 @@ bool CoordinateSystem::isFloating() const } template -void CoordinateSystem::serialize(Archive &ar, ATTRIBUTE(maybe_unused) const unsigned int version) { +void CoordinateSystem::serialize(Archive &ar, const unsigned int /* version */) { ar & m_isFloating; ar & boost::serialization::make_array(m_absolutePosition.data(), 3); ar & boost::serialization::make_array(m_absoluteRotation.data(), 3); diff --git a/src/datastructure/CovisibilityGraph.cpp b/src/datastructure/CovisibilityGraph.cpp index e5b5b61a..13a64da2 100644 --- a/src/datastructure/CovisibilityGraph.cpp +++ b/src/datastructure/CovisibilityGraph.cpp @@ -325,7 +325,7 @@ FrameworkReturnCode CovisibilityGraph::display() const } template -void CovisibilityGraph::serialize(Archive &ar, ATTRIBUTE(maybe_unused) const unsigned int version) +void CovisibilityGraph::serialize(Archive &ar, const unsigned int /* version */) { ar & m_nodes; ar & m_edges; diff --git a/src/datastructure/DescriptorBuffer.cpp b/src/datastructure/DescriptorBuffer.cpp index a95660ae..47667248 100644 --- a/src/datastructure/DescriptorBuffer.cpp +++ b/src/datastructure/DescriptorBuffer.cpp @@ -33,7 +33,7 @@ const static std::map> d }; DescriptorView::DescriptorView(void * startAddress, uint32_t length, DescriptorType type): - m_length(length),m_baseAddress(startAddress), m_type(type) + m_baseAddress(startAddress), m_length(length), m_type(type) { m_dataType = descriptorType2elementsAndDataType.at(type).second; } @@ -65,7 +65,7 @@ bool DescriptorBuffer::deduceProperties(const DescriptorType & type) } DescriptorBuffer::DescriptorBuffer( DescriptorType descriptor_type, uint32_t nb_descriptors): - m_nb_descriptors(nb_descriptors),m_descriptor_type(descriptor_type),m_buffer(new BufferInternal()) + m_buffer(new BufferInternal()), m_nb_descriptors(nb_descriptors), m_descriptor_type(descriptor_type) { if (!deduceProperties(descriptor_type)) { // ERROR no automatic translation : should throw an exception @@ -76,7 +76,7 @@ DescriptorBuffer::DescriptorBuffer( DescriptorType descriptor_type, uint32_t nb_ } DescriptorBuffer::DescriptorBuffer( unsigned char* descriptorData, DescriptorType descriptor_type, uint32_t nb_descriptors): - m_nb_descriptors(nb_descriptors),m_descriptor_type(descriptor_type),m_buffer(new BufferInternal()) + m_buffer(new BufferInternal()), m_nb_descriptors(nb_descriptors), m_descriptor_type(descriptor_type) { if (!deduceProperties(descriptor_type)) { // ERROR no automatic translation : should throw an exception @@ -183,7 +183,7 @@ DescriptorBuffer DescriptorBuffer::operator+(const DescriptorBuffer & desc) cons float *desc1_data = reinterpret_cast(desc1.data()); float *desc2_data = reinterpret_cast(desc2.data()); std::vector output(m_nb_descriptors * m_nb_elements); - for (int i = 0; i < output.size(); i++) + for (size_t i = 0; i < output.size(); i++) output[i] = desc1_data[i] + desc2_data[i]; return DescriptorBuffer(reinterpret_cast(output.data()), m_descriptor_type, TYPE_32F, m_nb_elements, m_nb_descriptors); } @@ -193,7 +193,7 @@ DescriptorBuffer DescriptorBuffer::operator*(float fac) const DescriptorBuffer desc = this->convertTo(TYPE_32F); float *desc_data = reinterpret_cast(desc.data()); std::vector output(m_nb_descriptors * m_nb_elements); - for (int i = 0; i < output.size(); i++) + for (size_t i = 0; i < output.size(); i++) output[i] = desc_data[i] * fac; return DescriptorBuffer(reinterpret_cast(output.data()), m_descriptor_type, TYPE_32F, m_nb_elements, m_nb_descriptors); } @@ -203,7 +203,7 @@ DescriptorBuffer DescriptorBuffer::operator/(float div) const DescriptorBuffer desc = this->convertTo(TYPE_32F); float *desc_data = reinterpret_cast(desc.data()); std::vector output(m_nb_descriptors * m_nb_elements); - for (int i = 0; i < output.size(); i++) + for (size_t i = 0; i < output.size(); i++) output[i] = desc_data[i] / div; return DescriptorBuffer(reinterpret_cast(output.data()), m_descriptor_type, TYPE_32F, m_nb_elements, m_nb_descriptors); } @@ -219,7 +219,7 @@ void DescriptorBuffer::append(const DescriptorView & descriptor) } template -void DescriptorBuffer::serialize(Archive &ar, ATTRIBUTE(maybe_unused) const unsigned int version) { +void DescriptorBuffer::serialize(Archive &ar, const unsigned int /* version */) { ar & m_buffer; ar & m_nb_descriptors; ar & m_data_type; diff --git a/src/datastructure/DescriptorMatch.cpp b/src/datastructure/DescriptorMatch.cpp index cc58904d..c903e49c 100644 --- a/src/datastructure/DescriptorMatch.cpp +++ b/src/datastructure/DescriptorMatch.cpp @@ -22,7 +22,7 @@ namespace SolAR { namespace datastructure { template -void DescriptorMatch::serialize(Archive &ar, ATTRIBUTE(maybe_unused) const unsigned int version) +void DescriptorMatch::serialize(Archive &ar, const unsigned int /* version */) { ar & std::get<0>(m_match); ar & std::get<1>(m_match); diff --git a/src/datastructure/FiducialMarker.cpp b/src/datastructure/FiducialMarker.cpp index 29ccce03..e762770b 100644 --- a/src/datastructure/FiducialMarker.cpp +++ b/src/datastructure/FiducialMarker.cpp @@ -49,7 +49,7 @@ SquaredBinaryPattern FiducialMarker::getPattern() const { } template -void FiducialMarker::serialize(Archive &ar, ATTRIBUTE(maybe_unused) const unsigned int version) { +void FiducialMarker::serialize(Archive &ar, const unsigned int /* version */) { ar.template register_type(); ar & boost::serialization::base_object(*this); diff --git a/src/datastructure/Frame.cpp b/src/datastructure/Frame.cpp index e984362c..f4902621 100644 --- a/src/datastructure/Frame.cpp +++ b/src/datastructure/Frame.cpp @@ -28,15 +28,15 @@ std::mutex m_mutexVisibility; namespace SolAR { namespace datastructure { -Frame::Frame(const SRef frame) : m_keypoints(frame->getKeypoints()), m_keypointsUndistort(frame->getUndistortedKeypoints()), m_descriptors(frame->getDescriptors()), m_view(frame->getView()), m_referenceKeyFrame(frame->getReferenceKeyframe()), m_pose(frame->getPose()), m_mapVisibility(frame->getVisibility()), m_imageName(frame->getImageName()), m_camID(frame->getCameraID()), m_isFixedPose(frame->isFixedPose()){} +Frame::Frame(const SRef frame) : m_pose(frame->getPose()), m_view(frame->getView()), m_referenceKeyFrame(frame->getReferenceKeyframe()), m_descriptors(frame->getDescriptors()), m_keypoints(frame->getKeypoints()), m_keypointsUndistort(frame->getUndistortedKeypoints()), m_imageName(frame->getImageName()), m_camID(frame->getCameraID()), m_isFixedPose(frame->isFixedPose()), m_mapVisibility(frame->getVisibility()){} -Frame::Frame(const SRef keyframe) : m_keypoints(keyframe->getKeypoints()), m_keypointsUndistort(keyframe->getUndistortedKeypoints()), m_descriptors(keyframe->getDescriptors()), m_view(keyframe->getView()), m_referenceKeyFrame(keyframe->getReferenceKeyframe()), m_pose(keyframe->getPose()), m_mapVisibility(keyframe->getVisibility()), m_imageName(keyframe->getImageName()), m_camID(keyframe->getCameraID()), m_isFixedPose(keyframe->isFixedPose()) {} +Frame::Frame(const SRef keyframe) : m_pose(keyframe->getPose()), m_view(keyframe->getView()), m_referenceKeyFrame(keyframe->getReferenceKeyframe()), m_descriptors(keyframe->getDescriptors()), m_keypoints(keyframe->getKeypoints()), m_keypointsUndistort(keyframe->getUndistortedKeypoints()), m_imageName(keyframe->getImageName()), m_camID(keyframe->getCameraID()), m_isFixedPose(keyframe->isFixedPose()), m_mapVisibility(keyframe->getVisibility()) {} -Frame::Frame(const std::vector& keypoints, const SRef descriptors, const SRef view, const uint32_t camID, const Transform3Df pose) : m_keypoints(keypoints), m_descriptors(descriptors), m_view(view), m_camID(camID), m_pose(pose) {} +Frame::Frame(const std::vector& keypoints, const SRef descriptors, const SRef view, const uint32_t camID, const Transform3Df pose) : m_pose(pose), m_view(view), m_descriptors(descriptors), m_keypoints(keypoints), m_camID(camID) {} -Frame::Frame(const std::vector & keypoints, const std::vector & undistortedKeypoints, const SRef descriptors, const SRef view, SRef refKeyframe, const uint32_t camID, const Transform3Df pose): m_keypoints(keypoints), m_keypointsUndistort(undistortedKeypoints), m_descriptors(descriptors), m_view(view), m_referenceKeyFrame(refKeyframe), m_camID(camID), m_pose(pose){} +Frame::Frame(const std::vector & keypoints, const std::vector & undistortedKeypoints, const SRef descriptors, const SRef view, SRef refKeyframe, const uint32_t camID, const Transform3Df pose): m_pose(pose), m_view(view), m_referenceKeyFrame(refKeyframe), m_descriptors(descriptors), m_keypoints(keypoints), m_keypointsUndistort(undistortedKeypoints), m_camID(camID){} -Frame::Frame(const std::vector & keypoints, const std::vector & undistortedKeypoints, const SRef descriptors, const SRef view, const uint32_t camID, const Transform3Df pose): m_keypoints(keypoints), m_keypointsUndistort(undistortedKeypoints), m_descriptors(descriptors), m_view(view), m_camID(camID), m_pose(pose){} +Frame::Frame(const std::vector & keypoints, const std::vector & undistortedKeypoints, const SRef descriptors, const SRef view, const uint32_t camID, const Transform3Df pose): m_pose(pose), m_view(view), m_descriptors(descriptors), m_keypoints(keypoints), m_keypointsUndistort(undistortedKeypoints), m_camID(camID) {} const SRef& Frame::getView() const { @@ -140,7 +140,7 @@ void Frame::addVisibility(const uint32_t& id_keypoint, const uint32_t& id_cloudP m_mapVisibility[id_keypoint] = id_cloudPoint; } -bool Frame::removeVisibility(const uint32_t& id_keypoint, ATTRIBUTE(maybe_unused) const uint32_t& id_cloudPoint) +bool Frame::removeVisibility(const uint32_t& id_keypoint, const uint32_t& /* id_cloudPoint */) { std::unique_lock lock(m_mutexVisibility); if (m_mapVisibility.find(id_keypoint) == m_mapVisibility.end()) @@ -196,7 +196,7 @@ const std::string& Frame::getImageName() const } template -void Frame::serialize(Archive &ar, ATTRIBUTE(maybe_unused) const unsigned int version) { +void Frame::serialize(Archive &ar, const unsigned int /* version */) { ar & boost::serialization::make_array(m_pose.data(), 12); ar & m_view; ar & m_descriptors; diff --git a/src/datastructure/Identification.cpp b/src/datastructure/Identification.cpp index c124b1df..8dcf145f 100644 --- a/src/datastructure/Identification.cpp +++ b/src/datastructure/Identification.cpp @@ -107,7 +107,7 @@ const BBox3Df& Identification::getBBox3D() const{ } template -void Identification::serialize(ATTRIBUTE(maybe_unused) Archive &ar, ATTRIBUTE(maybe_unused) const unsigned int version) { +void Identification::serialize(Archive & ar, const unsigned int /* version */) { ar & m_uuid; ar & m_name; ar & m_author; diff --git a/src/datastructure/Image.cpp b/src/datastructure/Image.cpp index 5277b415..3ef576db 100644 --- a/src/datastructure/Image.cpp +++ b/src/datastructure/Image.cpp @@ -63,7 +63,7 @@ void ImageInternal::setData(void * data, uint32_t size) } template -void ImageInternal::serialize(Archive &ar, ATTRIBUTE(maybe_unused) const unsigned int version) +void ImageInternal::serialize(Archive &ar, const unsigned int /* version */) { ar & m_storageData; ar & m_bufferSize; @@ -89,7 +89,7 @@ uint32_t Image::computeImageBufferSize() return m_size.width * m_size.height * m_nbChannels * (m_nbBitsPerComponent/8); } -Image::Image(enum ImageLayout imgLayout, enum PixelOrder pixOrder, DataType type):m_layout(imgLayout),m_pixOrder(pixOrder),m_type(type),m_internalImpl(new ImageInternal()) +Image::Image(enum ImageLayout imgLayout, enum PixelOrder pixOrder, DataType type):m_internalImpl(new ImageInternal()), m_layout(imgLayout),m_pixOrder(pixOrder),m_type(type) { m_nbChannels = layoutChannelMapInfos.at(m_layout); m_nbBitsPerComponent = typeSizeMapInfos.at(m_type); @@ -288,7 +288,7 @@ FrameworkReturnCode Image::save(std::string imagePath) const } template -void Image::save(Archive & ar, const unsigned int version) const +void Image::save(Archive & ar, const unsigned int /* version */) const { ar & m_size; ar & m_layout; @@ -407,13 +407,13 @@ FrameworkReturnCode Image::load(std::string imagePath) else { std::cout << "Try to decode an image with unsupported channels. Only RGB, GRB, BGR, RGBA and Grey are supported"; - FrameworkReturnCode::_ERROR_LOAD_IMAGE; + return FrameworkReturnCode::_ERROR_LOAD_IMAGE; } m_nbChannels = (unsigned int)spec.nchannels; break; default: std::cout << "Error: Try to decode an image with " << spec.nchannels << " channels. Only 1, 3 or 4 channels are supported"; - FrameworkReturnCode::_ERROR_LOAD_IMAGE; + return FrameworkReturnCode::_ERROR_LOAD_IMAGE; } m_internalImpl = utils::make_shared(); @@ -424,7 +424,7 @@ FrameworkReturnCode Image::load(std::string imagePath) } template -void Image::load(Archive & ar, const unsigned int version) +void Image::load(Archive & ar, const unsigned int /* version */) { ar & m_size; ar & m_layout; diff --git a/src/datastructure/ImageMarker.cpp b/src/datastructure/ImageMarker.cpp index 1053f72d..a7f7bc07 100644 --- a/src/datastructure/ImageMarker.cpp +++ b/src/datastructure/ImageMarker.cpp @@ -66,7 +66,7 @@ FrameworkReturnCode ImageMarker::getImageCorners(std::vector & imageCo } template -void ImageMarker::serialize(Archive &ar, ATTRIBUTE(maybe_unused) const unsigned int version) { +void ImageMarker::serialize(Archive &ar, const unsigned int /* version */) { ar & m_image; } diff --git a/src/datastructure/Keyframe.cpp b/src/datastructure/Keyframe.cpp index 2dfca882..cde1e43b 100644 --- a/src/datastructure/Keyframe.cpp +++ b/src/datastructure/Keyframe.cpp @@ -52,7 +52,7 @@ const std::vector& Keyframe::getIsKeypointMatched() const } template -void Keyframe::serialize(Archive &ar, ATTRIBUTE(maybe_unused) const unsigned int version) { +void Keyframe::serialize(Archive &ar, const unsigned int /* version */) { ar & boost::serialization::base_object(*this); ar & boost::serialization::base_object(*this); ar & m_id; diff --git a/src/datastructure/KeyframeCollection.cpp b/src/datastructure/KeyframeCollection.cpp index 4eb0c2f1..e6c8bf66 100644 --- a/src/datastructure/KeyframeCollection.cpp +++ b/src/datastructure/KeyframeCollection.cpp @@ -120,7 +120,7 @@ int KeyframeCollection::getNbKeyframes() const } template -void KeyframeCollection::serialize(Archive &ar, ATTRIBUTE(maybe_unused) const unsigned int version) +void KeyframeCollection::serialize(Archive &ar, const unsigned int /* version */) { ar & m_id; ar & m_descriptorType; diff --git a/src/datastructure/KeyframeRetrieval.cpp b/src/datastructure/KeyframeRetrieval.cpp index 0df00c4d..c6d51334 100644 --- a/src/datastructure/KeyframeRetrieval.cpp +++ b/src/datastructure/KeyframeRetrieval.cpp @@ -96,7 +96,7 @@ void KeyframeRetrieval::reset() } template -void KeyframeRetrieval::serialize(Archive &ar, ATTRIBUTE(maybe_unused) const unsigned int version) +void KeyframeRetrieval::serialize(Archive &ar, const unsigned int /* version */) { ar & m_listBoWFeature; ar & m_listBoWLevelFeature; diff --git a/src/datastructure/Keypoint.cpp b/src/datastructure/Keypoint.cpp index baf83548..d4c21b95 100644 --- a/src/datastructure/Keypoint.cpp +++ b/src/datastructure/Keypoint.cpp @@ -37,7 +37,7 @@ Keypoint::Keypoint( unsigned int id, float angle, float response, int octave, - int class_id ):m_id(id), Point2Df(x,y), m_rgb(r, g, b), m_size(size),m_angle(angle), m_response(response), m_octave(octave), m_class_id(class_id){ + int class_id ): Point2Df(x,y), m_id(id), m_size(size), m_angle(angle), m_response(response), m_octave(octave), m_class_id(class_id), m_rgb(r, g, b) { } @@ -65,7 +65,7 @@ void Keypoint::init(unsigned int id, } template -void Keypoint::serialize(Archive &ar, ATTRIBUTE(maybe_unused) const unsigned int version) { +void Keypoint::serialize(Archive &ar, const unsigned int /* version */) { ar & boost::serialization::base_object(*this); ar & boost::serialization::make_array(m_rgb.data(), 3); ar & m_id; diff --git a/src/datastructure/Map.cpp b/src/datastructure/Map.cpp index afd747cd..ec26612b 100644 --- a/src/datastructure/Map.cpp +++ b/src/datastructure/Map.cpp @@ -157,7 +157,7 @@ TrackableType Map::getType() const } template -void Map::serialize(Archive &ar, ATTRIBUTE(maybe_unused) const unsigned int version) { +void Map::serialize(Archive &ar, const unsigned int /* version */) { ar & m_mapSupportedTypes; ar & m_identification; ar & m_coordinateSystem; diff --git a/src/datastructure/Mesh.cpp b/src/datastructure/Mesh.cpp index 26b07199..2467f66e 100644 --- a/src/datastructure/Mesh.cpp +++ b/src/datastructure/Mesh.cpp @@ -39,7 +39,7 @@ Mesh::Mesh(const std::vector points, template -void Mesh::serialize(Archive &ar, ATTRIBUTE(maybe_unused) const unsigned int version) { +void Mesh::serialize(Archive &ar, const unsigned int /* version */) { ar & m_points; ar & m_indexedFaceSets; ar & m_normals; diff --git a/src/datastructure/PointCloud.cpp b/src/datastructure/PointCloud.cpp index 56fe885f..2fa1db69 100644 --- a/src/datastructure/PointCloud.cpp +++ b/src/datastructure/PointCloud.cpp @@ -157,7 +157,7 @@ int PointCloud::getNbPoints() const } template -void PointCloud::serialize(Archive &ar, ATTRIBUTE(maybe_unused) const unsigned int version) +void PointCloud::serialize(Archive &ar, const unsigned int /* version */) { ar & m_id; ar & m_descriptorType; diff --git a/src/datastructure/PrimitiveInformation.cpp b/src/datastructure/PrimitiveInformation.cpp index 87d5ef74..82078e7f 100644 --- a/src/datastructure/PrimitiveInformation.cpp +++ b/src/datastructure/PrimitiveInformation.cpp @@ -73,7 +73,7 @@ void PrimitiveInformation::setSemanticId(const int& semanticId) { } template -void PrimitiveInformation::serialize(Archive &ar, ATTRIBUTE(maybe_unused) const unsigned int version) +void PrimitiveInformation::serialize(Archive &ar, const unsigned int /* version */) { ar & m_confidence; ar & m_usedTimes; diff --git a/src/datastructure/QRCode.cpp b/src/datastructure/QRCode.cpp index d830788d..27e4648b 100644 --- a/src/datastructure/QRCode.cpp +++ b/src/datastructure/QRCode.cpp @@ -41,7 +41,7 @@ std::string QRCode::getCode() const { } template -void QRCode::serialize(Archive &ar, ATTRIBUTE(maybe_unused) const unsigned int version) { +void QRCode::serialize(Archive &ar, const unsigned int /* version */) { ar.template register_type(); ar & boost::serialization::base_object(*this); diff --git a/src/datastructure/SquaredBinaryPattern.cpp b/src/datastructure/SquaredBinaryPattern.cpp index 9dad75ec..6f08a447 100644 --- a/src/datastructure/SquaredBinaryPattern.cpp +++ b/src/datastructure/SquaredBinaryPattern.cpp @@ -49,7 +49,7 @@ FrameworkReturnCode SquaredBinaryPattern::setPatternMatrix (const SquaredBinaryP }; template -void SquaredBinaryPattern::serialize(Archive &ar, ATTRIBUTE(maybe_unused) const unsigned int version) +void SquaredBinaryPattern::serialize(Archive &ar, const unsigned int /* version */) { ar & m_size; ar & m_patternMatrix; diff --git a/src/datastructure/Trackable.cpp b/src/datastructure/Trackable.cpp index 9756e924..9de1a7da 100644 --- a/src/datastructure/Trackable.cpp +++ b/src/datastructure/Trackable.cpp @@ -46,7 +46,7 @@ void Trackable::setTransform3D(const datastructure::Transform3Df & transform3D){ } template -void Trackable::serialize(Archive &ar, ATTRIBUTE(maybe_unused) const unsigned int version) { +void Trackable::serialize(Archive &ar, const unsigned int /* version */) { ar & m_url; } diff --git a/src/datastructure/Trackable2D.cpp b/src/datastructure/Trackable2D.cpp index f1c15fb4..c7a0da17 100644 --- a/src/datastructure/Trackable2D.cpp +++ b/src/datastructure/Trackable2D.cpp @@ -88,7 +88,7 @@ FrameworkReturnCode Trackable2D::getWorldCorners(std::vector & worldCo } template -void Trackable2D::serialize(Archive &ar, ATTRIBUTE(maybe_unused) const unsigned int version) { +void Trackable2D::serialize(Archive &ar, const unsigned int /* version */) { ar & boost::serialization::base_object(*this);