@@ -40,29 +40,29 @@ class XPCF_IGNORE SOLARFRAMEWORK_API AMappingPipeline : public org::bcom::xpcf::
40
40
// / @brief Set the camera parameters
41
41
// / @param[in] cameraParams: the camera parameters (its resolution and its focal)
42
42
// / @return FrameworkReturnCode::_SUCCESS if the camera parameters are correctly set, else FrameworkReturnCode::_ERROR_
43
- virtual FrameworkReturnCode setCameraParameters (const SolAR::datastructure::CameraParameters & /* cameraParams */ ) override
43
+ virtual FrameworkReturnCode setCameraParameters ([[maybe_unused]] const SolAR::datastructure::CameraParameters & cameraParams) override
44
44
{ return FrameworkReturnCode::_NOT_IMPLEMENTED; }
45
45
46
46
// / @brief Set the camera parameters (use for stereo camera)
47
47
// / @param[in] cameraParams1 the camera parameters of the first camera
48
48
// / @param[in] cameraParams2 the camera parameters of the second camera
49
49
// / @return FrameworkReturnCode::_SUCCESS if the camera parameters are correctly set, else FrameworkReturnCode::_ERROR_
50
- virtual FrameworkReturnCode setCameraParameters (const SolAR::datastructure::CameraParameters & /* cameraParams1 */ ,
51
- const SolAR::datastructure::CameraParameters & /* cameraParams2 */ ) override
50
+ virtual FrameworkReturnCode setCameraParameters ([[maybe_unused]] const SolAR::datastructure::CameraParameters & cameraParams1,
51
+ [[maybe_unused]] const SolAR::datastructure::CameraParameters & cameraParams2) override
52
52
{ return FrameworkReturnCode::_NOT_IMPLEMENTED; }
53
53
54
54
// / @brief Set the rectification parameters (use for stereo camera)
55
55
// / @param[in] rectCam1 the rectification parameters of the first camera
56
56
// / @param[in] rectCam2 the rectification parameters of the second camera
57
57
// / @return FrameworkReturnCode::_SUCCESS if the rectification parameters are correctly set, else FrameworkReturnCode::_ERROR_
58
- virtual FrameworkReturnCode setRectificationParameters (const SolAR::datastructure::RectificationParameters & /* rectCam1 */ ,
59
- const SolAR::datastructure::RectificationParameters & /* rectCam2 */ ) override
58
+ virtual FrameworkReturnCode setRectificationParameters ([[maybe_unused]] const SolAR::datastructure::RectificationParameters & rectCam1,
59
+ [[maybe_unused]] const SolAR::datastructure::RectificationParameters & rectCam2) override
60
60
{ return FrameworkReturnCode::_NOT_IMPLEMENTED; }
61
61
62
62
// / @brief Set the 3D transformation from SolAR to world spaces
63
63
// / @param[in] transform the transformation matrix from SolAR to World
64
64
// / @return FrameworkReturnCode::_SUCCESS if the transform is correctly set, else FrameworkReturnCode::_ERROR_
65
- virtual FrameworkReturnCode set3DTransformSolARToWorld (const SolAR::datastructure::Transform3Df & /* transform*/ ) override
65
+ virtual FrameworkReturnCode set3DTransformSolARToWorld ([[maybe_unused]] const SolAR::datastructure::Transform3Df & transform) override
66
66
{ return FrameworkReturnCode::_NOT_IMPLEMENTED; }
67
67
68
68
// / @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::
73
73
// / @param[out] updatedTransform the refined transformation by a loop closure detection
74
74
// / @param[out] status the current status of the mapping pipeline
75
75
// / @return FrameworkReturnCode::_SUCCESS if the data are ready to be processed, else FrameworkReturnCode::_ERROR_
76
- virtual FrameworkReturnCode mappingProcessRequest (const std::vector<SRef<SolAR::datastructure::Image>> & /* images */ ,
77
- const std::vector<SolAR::datastructure::Transform3Df> & /* poses*/ ,
78
- bool /* fixedPose*/ ,
79
- const SolAR::datastructure::Transform3Df & /* transform*/ ,
80
- SolAR::datastructure::Transform3Df & /* updatedTransform*/ ,
81
- SolAR::api::pipeline::MappingStatus & /* status*/ ) override
76
+ virtual FrameworkReturnCode mappingProcessRequest ([[maybe_unused]] const std::vector<SRef<SolAR::datastructure::Image>> & images,
77
+ [[maybe_unused]] const std::vector<SolAR::datastructure::Transform3Df> & poses,
78
+ [[maybe_unused]] bool fixedPose,
79
+ [[maybe_unused]] const SolAR::datastructure::Transform3Df & transform,
80
+ [[maybe_unused]] SolAR::datastructure::Transform3Df & updatedTransform,
81
+ [[maybe_unused]] SolAR::api::pipeline::MappingStatus & status) override
82
82
{ return FrameworkReturnCode::_NOT_IMPLEMENTED; }
83
83
84
84
// / @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::
110
110
// / @param[out] outputPointClouds: pipeline current point clouds
111
111
// / @param[out] keyframePoses: pipeline current keyframe poses
112
112
// / @return FrameworkReturnCode::_SUCCESS if data are available, else FrameworkReturnCode::_ERROR_
113
- virtual FrameworkReturnCode getDataForVisualization (std::vector<SRef<SolAR::datastructure::CloudPoint>> & /* outputPointClouds*/ ,
114
- std::vector<SolAR::datastructure::Transform3Df> & /* keyframePoses*/ ) const override
113
+ virtual FrameworkReturnCode getDataForVisualization ([[maybe_unused]] std::vector<SRef<SolAR::datastructure::CloudPoint>>& outputPointClouds,
114
+ [[maybe_unused]] std::vector<SolAR::datastructure::Transform3Df>& keyframePoses) const override
115
115
{ return FrameworkReturnCode::_NOT_IMPLEMENTED; }
116
116
};
117
117
}
0 commit comments