Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
6 changes: 6 additions & 0 deletions SolARFramework.pri
Original file line number Diff line number Diff line change
Expand Up @@ -62,6 +62,7 @@ interfaces/api/output/files/IMeshExporter.h \
interfaces/api/output/files/IPointCloudExporter.h \
interfaces/api/output/files/IMapExporter.h \
interfaces/api/pipeline/IDenseMappingPipeline.h \
interfaces/api/pipeline/IImageSegmentationPipeline.h \
interfaces/api/pipeline/IMappingPipeline.h \
interfaces/api/pipeline/IMapUpdatePipeline.h \
interfaces/api/pipeline/IPipeline.h \
Expand Down Expand Up @@ -114,6 +115,7 @@ interfaces/api/storage/ICameraParametersManager.h \
interfaces/api/storage/IPointCloudManager.h \
interfaces/api/storage/IWorldGraphManager.h \
interfaces/api/storage/IMapManager.h \
interfaces/api/storage/IMasks2DManager.h \
interfaces/api/tracking/IOpticalFlowEstimator.h \
interfaces/core/Log.h \
interfaces/core/Timer.h \
Expand All @@ -138,6 +140,8 @@ interfaces/datastructure/Image.h \
interfaces/datastructure/ImageMarker.h \
interfaces/datastructure/Keyframe.h \
interfaces/datastructure/Keypoint.h \
interfaces/datastructure/Mask2D.h \
interfaces/datastructure/Mask2DCollection.h \
interfaces/datastructure/MathDefinitions.h \
interfaces/datastructure/Mesh.h \
interfaces/datastructure/PointCloud.h \
Expand Down Expand Up @@ -200,6 +204,8 @@ src/datastructure/CovisibilityGraph.cpp \
src/datastructure/KeyframeRetrieval.cpp \
src/datastructure/KeyframeCollection.cpp \
src/datastructure/Map.cpp \
src/datastructure/Mask2D.cpp \
src/datastructure/Mask2DCollection.cpp \
src/datastructure/Mesh.cpp \
src/datastructure/StorageTrackable.cpp \
src/datastructure/StorageWorldAnchor.cpp \
Expand Down
100 changes: 100 additions & 0 deletions interfaces/api/pipeline/IImageSegmentationPipeline.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,100 @@
/**
* @copyright Copyright (c) 2025 B-com http://www.b-com.com/
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*/

#ifndef SOLAR_IMAGESEGMENTATIONPIPELINE_H
#define SOLAR_IMAGESEGMENTATIONPIPELINE_H

#include "api/pipeline/IPipeline.h"
#include "datastructure/Image.h"
#include "datastructure/Mask2DCollection.h"
#include <xpcf/core/helpers.h>

namespace SolAR {
using namespace datastructure;
namespace api {
namespace pipeline {

/**
* @class IImageSegmentationPipeline
* @brief <B>Defines an image segmentation pipeline.</B>
* <TT>UUID: 0a897dee-74f1-42de-a6c1-f7855e0f0bbb</TT>
*
* This class provides the interface to define an image segmentation pipeline.
*/

class XPCF_CLIENTUUID("2215b6ef-e6fa-455c-84c6-820d95630eb5") XPCF_SERVERUUID("40aede65-0170-4384-9623-6a9d320ae56d")
XPCF_GRPC_CLIENT_RECV_SIZE("-1") XPCF_GRPC_CLIENT_SEND_SIZE("-1")
IImageSegmentationPipeline : virtual public IPipeline {
public:

/// Status of image segmentation processing
enum class Status {
UNINITIALIZED, ///< processing not initialized
INITIALIZED, ///< processing correctly initialized, but not started
IN_PROGRESS, ///< processing in progress
COMPLETED, ///< processing completed
ABORTED ///< processing aborted before completion
};

/// @brief image segmentation status to string
static const std::map<Status, std::string> statusToString = {
{Status::UNINITIALIZED, "UNINITIALIZED"},
{Status::INITIALIZED, "INITIALIZED"},
{Status::IN_PROGRESS, "IN_PROGRESS"},
{Status::COMPLETED, "COMPLETED"},
{Status::ABORTED, "ABORTED"}
};

/// @brief default constructor
IImageSegmentationPipeline() = default;

/// @brief default destructor
virtual ~IImageSegmentationPipeline() = default;

/// @brief segmentation request from an input image
/// @param[in] image pointer to image
/// @return FrameworkReturnCode::_SUCCESS (segmentation succeeded) or FrameworkReturnCode::_ERROR_ (segmentation failed)
virtual FrameworkReturnCode segment(SRef<Image> image) = 0;

/// @brief segmentation request from a number of input images
/// @param[in] images list of pointers to images to be segmented
/// @param[in] temporalConsistency flag indicating whether the images are temporally consistent (true) or not (false)
/// @return FrameworkReturnCode::_SUCCESS (segmentation succeeded) or FrameworkReturnCode::_ERROR_ (segmentation failed)
virtual FrameworkReturnCode segment(const std::vector<SRef<Image>>& images, bool temporalConsistency = false) = 0;

/// @brief get status and progress percentage
/// @param[out] status the current image segmentation processing status
/// @param[out] progress the current progress percentage (valid value should be between 0 and 1)
/// @return FrameworkReturnCode::_SUCCESS if the status and progress are successfully retrieved, otherwise FrameworkReturnCode::_ERROR_
virtual FrameworkReturnCode getStatus(Status& status, float& progress) const = 0;

/// @brief get output masks
/// @param[out] mask output mask collection
/// @return FrameworkReturnCode::_SUCCESS (get output mask succeeded) or FrameworkReturnCode::_ERROR_ (get output mask failed)
virtual FrameworkReturnCode getOutputMask(SRef<Mask2DCollection>& mask) const = 0;

};

} // namespace pipeline
} // namespace api
} // namespace SolAR

XPCF_DEFINE_INTERFACE_TRAITS(SolAR::api::pipeline::IImageSegmentationPipeline,
"0a897dee-74f1-42de-a6c1-f7855e0f0bbb",
"IImageSegmentationPipeline",
"The interface to define an image segmentation pipeline")

#endif // SOLAR_IMAGESEGMENTATIONPIPELINE_H
12 changes: 12 additions & 0 deletions interfaces/api/storage/IMapManager.h
Original file line number Diff line number Diff line change
Expand Up @@ -32,6 +32,7 @@
#include "api/storage/ICameraParametersManager.h"
#include "api/storage/ICovisibilityGraphManager.h"
#include "api/storage/IKeyframesManager.h"
#include "api/storage/IMasks2DManager.h"
#include "api/storage/IPointCloudManager.h"
#include "api/reloc/IKeyframeRetriever.h"

Expand Down Expand Up @@ -109,6 +110,17 @@ class XPCF_IGNORE IMapManager :
/// @return FrameworkReturnCode::_SUCCESS if succeed, else FrameworkReturnCode::_ERROR_
virtual FrameworkReturnCode removeKeyframe(const SRef<SolAR::datastructure::Keyframe> keyframe) = 0;

/// @brief Add a 2d mask to map manager
/// @param[in] mask 2D mask to be added to map manager
/// @param[in] defineId if true an id will be set for the added mask, if false the id of the input mask will be used
/// @return FrameworkReturnCode::_SUCCESS if succeed, else FrameworkReturnCode::_ERROR_
virtual FrameworkReturnCode addMask2D(SRef<SolAR::datastructure::Mask2D> mask, bool defineId = true) = 0;

/// @brief remove mask
/// @param[in] id mask ID
/// @return FrameworkReturnCode::_SUCCESS if mask removed successfully, otherwise FrameworkReturnCode::_ERROR_
virtual FrameworkReturnCode removeMask2D(uint32_t id) = 0;

/// @brief Add camera parameters to map manager
/// @param[in] cameraParameters the camera paramaters to add to the map manager
/// @param[in] defineCameraParametersId if true an id will be set for the added CameraParameters, if false the id of the CameraParameters will be used
Expand Down
120 changes: 120 additions & 0 deletions interfaces/api/storage/IMasks2DManager.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,120 @@
/**
* @copyright Copyright (c) 2025 B-com http://www.b-com.com/
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*/

#ifndef SOLAR_I2DMASKSMANAGER_H
#define SOLAR_I2DMASKSMANAGER_H

#include "datastructure/Mask2DCollection.h"
#include <xpcf/api/IComponentIntrospect.h>

namespace SolAR {
using namespace datastructure;
namespace api {
namespace storage {

/**
* @class IMasks2DManager
* @brief <B>Allows to store a set of 2D masks.</B>
* <TT>UUID: 56f36544-85c4-4636-bd4e-b3493a9e95c4</TT>
*
* This storage component can be accessed by processing components to share persistent data.
*/

class XPCF_IGNORE IMasks2DManager : virtual public org::bcom::xpcf::IComponentIntrospect {
public:
/// @brief IMasks2DManager default constructor
IMasks2DManager() = default;

/// @brief IMasks2DManager default destructor
virtual ~IMasks2DManager() = default;

/// @brief This method allows to add a mask to the 2D mask manager component
/// @param[in] mask the mask to add to the set of persistent masks
/// @param[in] defineMaskId if true an id will be set for the added mask, if false the id of the mask will be used
/// @return FrameworkReturnCode::_SUCCESS_ if the addition succeed, else FrameworkReturnCode::_ERROR.
virtual FrameworkReturnCode addMask(SRef<Mask2D> mask, bool defineMaskId = true) = 0;

/// @brief This method allows to get a mask by its id
/// @param[in] id id of the mask to get
/// @param[out] mask a mask stored in the masks manager
/// @return FrameworkReturnCode::_SUCCESS_ if succeed, else FrameworkReturnCode::_ERROR.
virtual FrameworkReturnCode getMask(uint32_t id, SRef<Mask2D>& mask) const = 0;

/// @brief This method allows to get a set of masks by their ids
/// @param[in] ids a vector of ids of the masks to get
/// @param[out] masks a vector of masks stored in the mask manager
/// @return FrameworkReturnCode::_SUCCESS_ if succeed, else FrameworkReturnCode::_ERROR.
virtual FrameworkReturnCode getMasks(const std::vector<uint32_t>& ids, std::vector<SRef<Mask2D>>& masks) const = 0;

/// @brief This method allows to get all masks
/// @param[out] masks the set of masks
/// @return FrameworkReturnCode::_SUCCESS_ if succeed, else FrameworkReturnCode::_ERROR.
virtual FrameworkReturnCode getAllMasks(std::vector<SRef<Mask2D>>& masks) const = 0;

/// @brief This method allows to know if a mask is already stored in the component
/// @param[in] id id of this mask
/// @return true if exist, else false
virtual bool isExistMask(uint32_t id) const = 0;

/// @brief This method allows to get the number of masks stored in the component
/// @return The number of masks
virtual size_t getNbMasks() const = 0;

/// @brief This method allow to suppress a mask by its id
/// @param[in] id id of the mask to suppress
/// @return FrameworkReturnCode::_SUCCESS_ if the suppression succeed, else FrameworkReturnCode::_ERROR.
virtual FrameworkReturnCode suppressMask(uint32_t id) = 0;

/// @brief This method is to set the mask collection
/// @param[in] maskCollection the mask collection of map
virtual void setMaskCollection(SRef<Mask2DCollection> maskCollection) = 0;

/// @brief This method returns a pointer to the const mask collection
/// @return the mask collection
virtual SRef<const Mask2DCollection> getConstMaskCollection() const = 0;

/// @brief This method returns a pointer to the mask collection
/// @return the mask collection
virtual SRef<Mask2DCollection> getMaskCollection() const = 0;

/// @brief This method returns the mask collection
/// @param[out] maskCollection the mask collection of map
/// @return std::unique_lock<std::mutex> which can be used to lock the access to data
virtual std::unique_lock<std::mutex> getMaskCollection(SRef<Mask2DCollection>& maskCollection) = 0;

/// @brief This method allows to save the masks to the external file
/// @param[in] file the file name
/// @return FrameworkReturnCode::_SUCCESS_ if the save succeeded, else FrameworkReturnCode::_ERROR.
virtual FrameworkReturnCode saveToFile(const std::string& file) const = 0;

/// @brief This method allows to load the masks from the external file
/// @param[in] file the file name
/// @return FrameworkReturnCode::_SUCCESS_ if the load succeeded, else FrameworkReturnCode::_ERROR.
virtual FrameworkReturnCode loadFromFile(const std::string& file) = 0;
};

} // storage
} // api
} // SolAR

XPCF_DEFINE_INTERFACE_TRAITS(SolAR::api::storage::IMasks2DManager,
"56f36544-85c4-4636-bd4e-b3493a9e95c4",
"IMasks2DManager",
"A component interface for storing a set of 2D masks accessible by processing components.");



#endif
18 changes: 9 additions & 9 deletions interfaces/datastructure/Frame.h
Original file line number Diff line number Diff line change
@@ -1,7 +1,6 @@
#ifndef FRAME_H
#define FRAME_H


#include <core/SolARFrameworkDefinitions.h>
#include <core/SerializationDefinitions.h>
#include <datastructure/GeometryDefinitions.h>
Expand All @@ -11,8 +10,8 @@
#include <datastructure/CloudPoint.h>
#include <datastructure/CameraDefinitions.h>
#include <datastructure/GlobalDescriptor.h>

#include <memory>

namespace SolAR {
namespace datastructure {

Expand Down Expand Up @@ -57,17 +56,17 @@ class SOLARFRAMEWORK_API Frame {
/// @return view image
const SRef<Image>& getView() const;

/// @brief get mask
/// @return mask
const SRef<Image> getMask() const;
/// @brief get mask IDs
/// @return vector of mask IDs
const std::vector<uint32_t>& getMaskIDs() const;

/// @brief set view image
/// @param[in] view: view image
void setView(const SRef<Image> &view);

/// @brief set mask
/// @param[in] mask semantic segmentation mask
void setMask(const SRef<Image> mask);
/// @brief set mask IDs
/// @param[in] maskIDs mask IDs
void setMaskIDs(const std::vector<uint32_t>& maskIDs);

/// @brief get camera pose
/// @return camera pose
Expand Down Expand Up @@ -198,7 +197,7 @@ class SOLARFRAMEWORK_API Frame {
protected:
Transform3Df m_pose;
SRef<Image> m_view;
SRef<Image> m_mask; // to store 2D image segmentation result
std::vector<uint32_t> m_maskIDs;
SRef<Keyframe> m_referenceKeyFrame ;
SRef<DescriptorBuffer> m_descriptors;
SRef<GlobalDescriptor> m_globalDescriptor;
Expand All @@ -219,5 +218,6 @@ DECLARESERIALIZE(Frame);
}

BOOST_CLASS_EXPORT_KEY(SolAR::datastructure::Frame);
BOOST_CLASS_VERSION(SolAR::datastructure::Frame, 1);

#endif // FRAME_H
22 changes: 22 additions & 0 deletions interfaces/datastructure/Map.h
Original file line number Diff line number Diff line change
Expand Up @@ -28,6 +28,7 @@
#include <datastructure/KeyframeCollection.h>
#include <datastructure/CovisibilityGraph.h>
#include <datastructure/KeyframeRetrieval.h>
#include <datastructure/Mask2DCollection.h>
#include <Version.h>
#include <xpcf/core/refs.h>
#include <vector>
Expand Down Expand Up @@ -150,6 +151,23 @@ class SOLARFRAMEWORK_API Map : public Trackable {
///
void setKeyframeCollection(const SRef<KeyframeCollection> keyframeCollection);

/// @brief This method returns a pointer to the const 2D mask collection
/// @return pointer to const mask collection
const Mask2DCollection& getConstMask2DCollection() const;

/// @brief This method returns a pointer to the 2D mask collection
/// @return pointer to the mask collection
SRef<Mask2DCollection> getMask2DCollection() const;

/// @brief This method returns the 2D mask collection
/// @param[out] maskCollection the mask collection of map
/// @return std::unique_lock<std::mutex> which can be used to lock the access to data
std::unique_lock<std::mutex> getMask2DCollection(SRef<Mask2DCollection>& maskCollection);

/// @brief This method is to set the 2D mask collection
/// @param[in] maskCollection the 2D mask collection of map
void setMask2DCollection(SRef<Mask2DCollection> maskCollection);

///
/// @brief This method returns the camera parameters collection
/// @return the camera parameters collection
Expand Down Expand Up @@ -275,6 +293,7 @@ class SOLARFRAMEWORK_API Map : public Trackable {
SRef<CoordinateSystem> m_coordinateSystem = org::bcom::xpcf::utils::make_shared<CoordinateSystem>();
SRef<PointCloud> m_pointCloud = org::bcom::xpcf::utils::make_shared<PointCloud>();
SRef<KeyframeCollection> m_keyframeCollection = org::bcom::xpcf::utils::make_shared<KeyframeCollection>();
SRef<Mask2DCollection> m_mask2DCollection = org::bcom::xpcf::utils::make_shared<Mask2DCollection>();
SRef<CovisibilityGraph> m_covisibilityGraph = org::bcom::xpcf::utils::make_shared<CovisibilityGraph>();
SRef<KeyframeRetrieval> m_keyframeRetrieval = org::bcom::xpcf::utils::make_shared<KeyframeRetrieval>();
SRef<CameraParametersCollection> m_cameraParametersCollection = org::bcom::xpcf::utils::make_shared<CameraParametersCollection>();
Expand All @@ -288,4 +307,7 @@ class SOLARFRAMEWORK_API Map : public Trackable {
DECLARESERIALIZE(Map);
}
} // end of namespace SolAR

BOOST_CLASS_VERSION(SolAR::datastructure::Map, 1);

#endif // SOLAR_MAP_H
Loading