Skip to content

Commit 6847a9e

Browse files
committed
Use [[maybe_unused]] to address unused-parameter warning
1 parent f0e5bae commit 6847a9e

35 files changed

+93
-93
lines changed

interfaces/base/features/ADescriptorMatcher.h

+3-3
Original file line numberDiff line numberDiff line change
@@ -43,9 +43,9 @@ class XPCF_IGNORE SOLARFRAMEWORK_API ADescriptorMatcher : public org::bcom::xpcf
4343
/// @param[in] descriptors2 The second set of descriptors organized in a dedicated buffer structure.
4444
/// @param[out] matches A vector of matches representing pairs of indices relatively to the first and second set of descriptors.
4545
/// @return FrameworkReturnCode::_SUCCESS if matching succeed, else FrameworkReturnCode::_ERROR_
46-
virtual FrameworkReturnCode match(const SRef<SolAR::datastructure::DescriptorBuffer> /*descriptors1*/,
47-
const SRef<SolAR::datastructure::DescriptorBuffer> /*descriptors2*/,
48-
std::vector<SolAR::datastructure::DescriptorMatch> & /*matches*/) override
46+
virtual FrameworkReturnCode match([[maybe_unused]] const SRef<SolAR::datastructure::DescriptorBuffer> descriptors1,
47+
[[maybe_unused]] const SRef<SolAR::datastructure::DescriptorBuffer> descriptors2,
48+
[[maybe_unused]] std::vector<SolAR::datastructure::DescriptorMatch> & matches) override
4949
{ return FrameworkReturnCode::_NOT_IMPLEMENTED; }
5050

5151
/// @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.

interfaces/base/features/ADescriptorMatcherGeometric.h

+11-11
Original file line numberDiff line numberDiff line change
@@ -50,17 +50,17 @@ class XPCF_IGNORE SOLARFRAMEWORK_API ADescriptorMatcherGeometric : public org::b
5050
/// @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.
5151
/// @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.
5252
/// @return FrameworkReturnCode::_SUCCESS if matching succeed, else FrameworkReturnCode::_ERROR_
53-
virtual FrameworkReturnCode match(const SRef<SolAR::datastructure::DescriptorBuffer> /* descriptors1 */,
54-
const SRef<SolAR::datastructure::DescriptorBuffer> /* descriptors2 */,
55-
const std::vector<SolAR::datastructure::Keypoint> & /* undistortedKeypoints1, */,
56-
const std::vector<SolAR::datastructure::Keypoint> & /* undistortedKeypoints2 */,
57-
const SolAR::datastructure::Transform3Df& /* pose1, */,
58-
const SolAR::datastructure::Transform3Df& /* pose2 */,
59-
const SolAR::datastructure::CameraParameters & /* camParams1, */,
60-
const SolAR::datastructure::CameraParameters & /* camParams2 */,
61-
std::vector<SolAR::datastructure::DescriptorMatch> & /* matches */,
62-
const std::vector<uint32_t>& /* mask1 */,
63-
const std::vector<uint32_t>& /* mask2 */) override
53+
virtual FrameworkReturnCode match([[maybe_unused]] const SRef<SolAR::datastructure::DescriptorBuffer> descriptors1,
54+
[[maybe_unused]] const SRef<SolAR::datastructure::DescriptorBuffer> descriptors2,
55+
[[maybe_unused]] const std::vector<SolAR::datastructure::Keypoint> & undistortedKeypoints1,
56+
[[maybe_unused]] const std::vector<SolAR::datastructure::Keypoint> & undistortedKeypoints2,
57+
[[maybe_unused]] const SolAR::datastructure::Transform3Df& pose1,
58+
[[maybe_unused]] const SolAR::datastructure::Transform3Df& pose2,
59+
[[maybe_unused]] const SolAR::datastructure::CameraParameters & camParams1,
60+
[[maybe_unused]] const SolAR::datastructure::CameraParameters & camParams2,
61+
[[maybe_unused]] std::vector<SolAR::datastructure::DescriptorMatch> & matches,
62+
[[maybe_unused]] const std::vector<uint32_t>& mask1,
63+
[[maybe_unused]] const std::vector<uint32_t>& mask2) override
6464
{ return FrameworkReturnCode::_NOT_IMPLEMENTED; }
6565

6666
/// @brief Match two sets of descriptors from two frames based on epipolar constraint.

interfaces/base/features/ADescriptorMatcherRegion.h

+7-7
Original file line numberDiff line numberDiff line change
@@ -46,13 +46,13 @@ class XPCF_IGNORE SOLARFRAMEWORK_API ADescriptorMatcherRegion : public org::bcom
4646
/// @param[in] radius the radius of search region around each keypoint of the first set.
4747
/// @param[in] matchingDistanceMax the maximum distance to valid a match.
4848
/// @return FrameworkReturnCode::_SUCCESS if matching succeed, else FrameworkReturnCode::_ERROR_
49-
virtual FrameworkReturnCode match(const SRef<SolAR::datastructure::DescriptorBuffer> /*descriptors1*/,
50-
const SRef<SolAR::datastructure::DescriptorBuffer> /*descriptors2*/,
51-
const std::vector<SolAR::datastructure::Point2Df> & /*points2D1*/,
52-
const std::vector<SolAR::datastructure::Point2Df> & /*points2D2*/,
53-
std::vector<SolAR::datastructure::DescriptorMatch> &/*matches*/,
54-
const float /*radius = -1.f */,
55-
const float /*matchingDistanceMax = -1.f */) override
49+
virtual FrameworkReturnCode match([[maybe_unused]] const SRef<SolAR::datastructure::DescriptorBuffer> descriptors1,
50+
[[maybe_unused]] const SRef<SolAR::datastructure::DescriptorBuffer> descriptors2,
51+
[[maybe_unused]] const std::vector<SolAR::datastructure::Point2Df> & points2D1,
52+
[[maybe_unused]] const std::vector<SolAR::datastructure::Point2Df> & points2D2,
53+
[[maybe_unused]] std::vector<SolAR::datastructure::DescriptorMatch> & matches,
54+
[[maybe_unused]] const float radius = -1.f,
55+
[[maybe_unused]] const float matchingDistanceMax = -1.f) override
5656
{ return FrameworkReturnCode::_NOT_IMPLEMENTED;}
5757

5858
/// @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

interfaces/base/features/ADescriptorMatcherStereo.h

+6-6
Original file line numberDiff line numberDiff line change
@@ -45,12 +45,12 @@ class XPCF_IGNORE SOLARFRAMEWORK_API ADescriptorMatcherStereo : public org::bcom
4545
/// @param[in] type Stereo type (horizontal or vertical).
4646
/// @param[out] matches A vector of matches representing pairs of indices relatively to the first and second set of descriptors.
4747
/// @return FrameworkReturnCode::_SUCCESS if matching succeed, else FrameworkReturnCode::_ERROR_
48-
virtual FrameworkReturnCode match(const SRef<SolAR::datastructure::DescriptorBuffer>& /*descriptors1*/,
49-
const SRef<SolAR::datastructure::DescriptorBuffer>& /*descriptors2*/,
50-
const std::vector<SolAR::datastructure::Keypoint>& /*undistortedKeypoints1*/,
51-
const std::vector<SolAR::datastructure::Keypoint>& /*undistortedKeypoints2*/,
52-
SolAR::datastructure::StereoType /*type*/,
53-
std::vector<SolAR::datastructure::DescriptorMatch> &/*matches*/) override
48+
virtual FrameworkReturnCode match([[maybe_unused]] const SRef<SolAR::datastructure::DescriptorBuffer>& descriptors1,
49+
[[maybe_unused]] const SRef<SolAR::datastructure::DescriptorBuffer>& descriptors2,
50+
[[maybe_unused]] const std::vector<SolAR::datastructure::Keypoint>& undistortedKeypoints1,
51+
[[maybe_unused]] const std::vector<SolAR::datastructure::Keypoint>& undistortedKeypoints2,
52+
[[maybe_unused]] SolAR::datastructure::StereoType type,
53+
[[maybe_unused]] std::vector<SolAR::datastructure::DescriptorMatch>& matches) override
5454
{ return FrameworkReturnCode::_NOT_IMPLEMENTED; }
5555

5656
/// @brief Match two sets of descriptors from stereo images.

interfaces/base/geom/A2DPointsRectification.h

+4-4
Original file line numberDiff line numberDiff line change
@@ -43,10 +43,10 @@ class XPCF_IGNORE SOLARFRAMEWORK_API A2DPointsRectification : public org::bcom::
4343
/// @param[in] rectParams The rectification parameters of camera
4444
/// @param[out] rectifiedPoints2D The rectified 2D points
4545
/// @return FrameworkReturnCode::_SUCCESS if rectifying succeed, else FrameworkReturnCode::_ERROR_
46-
virtual FrameworkReturnCode rectify(const std::vector<SolAR::datastructure::Point2Df>& /*points2D*/,
47-
const SolAR::datastructure::CameraParameters& /*camParams*/,
48-
const SolAR::datastructure::RectificationParameters& /*rectParams*/,
49-
std::vector<SolAR::datastructure::Point2Df>& /*rectifiedPoints2D*/) override
46+
virtual FrameworkReturnCode rectify([[maybe_unused]] const std::vector<SolAR::datastructure::Point2Df>& points2D,
47+
[[maybe_unused]] const SolAR::datastructure::CameraParameters& camParams,
48+
[[maybe_unused]] const SolAR::datastructure::RectificationParameters& rectParams,
49+
[[maybe_unused]] std::vector<SolAR::datastructure::Point2Df>& rectifiedPoints2D) override
5050
{ return FrameworkReturnCode::_NOT_IMPLEMENTED; }
5151

5252
/// @brief Rectify 2D keypoints

interfaces/base/geom/AReprojectionStereo.h

+8-8
Original file line numberDiff line numberDiff line change
@@ -42,9 +42,9 @@ class XPCF_IGNORE SOLARFRAMEWORK_API AReprojectionStereo : public org::bcom::xpc
4242
/// @param[in] rectParams The rectification parameters.
4343
/// @param[out] unrectifiedKeypoints The unrectified keypoints for estimating depth information.
4444
/// @return FrameworkReturnCode::_SUCCESS if reprojecting succeed, else FrameworkReturnCode::_ERROR_
45-
virtual FrameworkReturnCode reprojectToUnrectification(const std::vector<SolAR::datastructure::Keypoint>& /*rectifiedKeypoints*/,
46-
const SolAR::datastructure::RectificationParameters& /*rectParams*/,
47-
std::vector<SolAR::datastructure::Keypoint>& /*unrectifiedKeypoints*/) override
45+
virtual FrameworkReturnCode reprojectToUnrectification([[maybe_unused]] const std::vector<SolAR::datastructure::Keypoint>& rectifiedKeypoints,
46+
[[maybe_unused]] const SolAR::datastructure::RectificationParameters& rectParams,
47+
[[maybe_unused]] std::vector<SolAR::datastructure::Keypoint>& unrectifiedKeypoints) override
4848
{ return FrameworkReturnCode::_NOT_IMPLEMENTED; }
4949

5050
/// @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
5454
/// @param[in] intrinsicParams The intrinsic parameters of the camera.
5555
/// @param[out] cloudPoints The output cloud points.
5656
/// @return FrameworkReturnCode::_SUCCESS if reprojecting succeed, else FrameworkReturnCode::_ERROR_
57-
virtual FrameworkReturnCode reprojectToCloudPoints(const std::vector<SolAR::datastructure::Keypoint>& /*undistortedKeypoints*/,
58-
const SRef<SolAR::datastructure::DescriptorBuffer> /*descriptors*/,
59-
const SolAR::datastructure::Transform3Df& /*pose*/,
60-
const SolAR::datastructure::CamCalibration& /*intrinsicParams*/,
61-
std::vector<SRef<SolAR::datastructure::CloudPoint>>& /*cloudPoints*/) override
57+
virtual FrameworkReturnCode reprojectToCloudPoints([[maybe_unused]] const std::vector<SolAR::datastructure::Keypoint>& undistortedKeypoints,
58+
[[maybe_unused]] const SRef<SolAR::datastructure::DescriptorBuffer> descriptors,
59+
[[maybe_unused]] const SolAR::datastructure::Transform3Df& pose,
60+
[[maybe_unused]] const SolAR::datastructure::CamCalibration& intrinsicParams,
61+
[[maybe_unused]] std::vector<SRef<SolAR::datastructure::CloudPoint>>& cloudPoints) override
6262
{ return FrameworkReturnCode::_NOT_IMPLEMENTED; }
6363

6464
/// @brief Reproject 2D keypoints with depths of a frame to 3D cloud points in the world coordinate system

interfaces/base/pipeline/AMappingPipeline.h

+14-14
Original file line numberDiff line numberDiff line change
@@ -40,29 +40,29 @@ class XPCF_IGNORE SOLARFRAMEWORK_API AMappingPipeline : public org::bcom::xpcf::
4040
/// @brief Set the camera parameters
4141
/// @param[in] cameraParams: the camera parameters (its resolution and its focal)
4242
/// @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
4444
{ return FrameworkReturnCode::_NOT_IMPLEMENTED; }
4545

4646
/// @brief Set the camera parameters (use for stereo camera)
4747
/// @param[in] cameraParams1 the camera parameters of the first camera
4848
/// @param[in] cameraParams2 the camera parameters of the second camera
4949
/// @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
5252
{ return FrameworkReturnCode::_NOT_IMPLEMENTED; }
5353

5454
/// @brief Set the rectification parameters (use for stereo camera)
5555
/// @param[in] rectCam1 the rectification parameters of the first camera
5656
/// @param[in] rectCam2 the rectification parameters of the second camera
5757
/// @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
6060
{ return FrameworkReturnCode::_NOT_IMPLEMENTED; }
6161

6262
/// @brief Set the 3D transformation from SolAR to world spaces
6363
/// @param[in] transform the transformation matrix from SolAR to World
6464
/// @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
6666
{ return FrameworkReturnCode::_NOT_IMPLEMENTED; }
6767

6868
/// @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::
7373
/// @param[out] updatedTransform the refined transformation by a loop closure detection
7474
/// @param[out] status the current status of the mapping pipeline
7575
/// @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
8282
{ return FrameworkReturnCode::_NOT_IMPLEMENTED; }
8383

8484
/// @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::
110110
/// @param[out] outputPointClouds: pipeline current point clouds
111111
/// @param[out] keyframePoses: pipeline current keyframe poses
112112
/// @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
115115
{ return FrameworkReturnCode::_NOT_IMPLEMENTED; }
116116
};
117117
}

interfaces/datastructure/BufferInternal.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -81,7 +81,7 @@ class BufferInternal {
8181
private:
8282
friend class boost::serialization::access;
8383
template<class Archive>
84-
void serialize(Archive &ar, const unsigned int /* version */) {
84+
void serialize(Archive &ar, [[maybe_unused]] const unsigned int version) {
8585
ar & m_storageData;
8686
ar & m_bufferSize;
8787
}

0 commit comments

Comments
 (0)