8 #ifndef META_OCEAN_TRACKING_ORB_FEATURE_MAP_H
9 #define META_OCEAN_TRACKING_ORB_FEATURE_MAP_H
59 FeatureMap(
const Frame& frame,
const Vector2& dimension,
const Scalar threshold =
Scalar(6.5),
const bool frameIsUndistorted =
true,
const unsigned int maxFeatures = 0u,
const bool useHarrisFeatures =
false,
Worker* worker =
nullptr);
85 bool projectToImagePlane(
const HomogenousMatrix4& pose,
const PinholeCamera& pinholeCamera,
const Scalar boundary,
int& left,
int& top,
unsigned int& width,
unsigned int& height,
unsigned int& leftClamped,
unsigned int& topClamped,
unsigned int& widthClamped,
unsigned int& heightClamped);
119 inline const Box3& boundingBox()
const;
127 inline const Plane3& plane()
const;
133 inline bool isPlanar()
const;
139 inline bool isUsingHarrisFeatures()
const;
145 inline bool isNull()
const;
151 explicit inline operator bool()
const;
225 inline FeatureMap::operator bool()
const
227 return !features_.empty();
This class implements Ocean's image class.
Definition: Frame.h:1792
bool isValid() const
Returns whether this plane is valid.
Definition: Plane3.h:538
This class implements a feature map for ORB features.
Definition: FeatureMap.h:39
const Plane3 & plane() const
Returns the plane of this feature map.
Definition: FeatureMap.h:210
bool isPlanar() const
Returns whether the feature map is planar.
Definition: FeatureMap.h:215
Box3 boundingBox_
Bounding box of the feature map enclosing all object features.
Definition: FeatureMap.h:176
CV::Detector::ORBFeatures features_
All object ORB features corresponding to this map.
Definition: FeatureMap.h:170
void setProjectedFeatures(CV::Detector::ORBFeatures &features)
Sets additional feature points that were projected from the camera plane to the 3D plane of the featu...
Definition: FeatureMap.h:190
CV::Detector::ORBFeatures projectedFeatures_
Optional projected ORB features.
Definition: FeatureMap.h:173
bool isUsingHarrisFeatures() const
Returns whether the feature map is using Harris corners or FAST features.
Definition: FeatureMap.h:220
bool projectToImagePlane(const HomogenousMatrix4 &pose, const PinholeCamera &pinholeCamera, const Scalar boundary, int &left, int &top, unsigned int &width, unsigned int &height, unsigned int &leftClamped, unsigned int &topClamped, unsigned int &widthClamped, unsigned int &heightClamped)
Projects the bounding box of the feature map into an image plane.
FeatureMap()
Creates an empty feature map.
const CV::Detector::ORBFeatures & projectedFeatures() const
Returns features that were projected from the camera plane to the 3D plane of the feature map.
Definition: FeatureMap.h:185
const CV::Detector::ORBFeatures & features() const
Returns all features determined during creation of the feature map.
Definition: FeatureMap.h:195
bool usingHarrisFeatures_
Definition: FeatureMap.h:182
Box2 projectToImagePlaneIF(const HomogenousMatrix4 &iFlippedPose, const PinholeCamera &pinholeCamera)
Projects the bounding box of the feature map into an image plane.
Plane3 plane_
Plane of the feature map if all feature points are planar.
Definition: FeatureMap.h:179
bool projectToImagePlaneIF(const HomogenousMatrix4 &iFlippedPose, const PinholeCamera &pinholeCamera, const Scalar boundary, unsigned int &left, unsigned int &top, unsigned int &width, unsigned int &height)
Projects the bounding box of the feature map into an image plane.
FeatureMap(const Frame &frame, const Vector2 &dimension, const Scalar threshold=Scalar(6.5), const bool frameIsUndistorted=true, const unsigned int maxFeatures=0u, const bool useHarrisFeatures=false, Worker *worker=nullptr)
Creates a new feature map by a given image frame.
Box2 projectToImagePlane(const HomogenousMatrix4 &pose, const PinholeCamera &pinholeCamera)
Projects the bounding box of the feature map into an image plane.
bool isNull() const
Returns whether this map holds no features.
Definition: FeatureMap.h:205
const Box3 & boundingBox() const
Returns the bounding box of this feature map.
Definition: FeatureMap.h:200
This class implements a worker able to distribute function calls over different threads.
Definition: Worker.h:33
std::vector< ORBFeature > ORBFeatures
Definition of a vector holding ORB features.
Definition: ORBFeature.h:26
float Scalar
Definition of a scalar type.
Definition: Math.h:128
The namespace covering the entire Ocean framework.
Definition: Accessor.h:15