8 #ifndef META_OCEAN_TRACKING_OFFLINE_SLAM_TRACKER_H
9 #define META_OCEAN_TRACKING_OFFLINE_SLAM_TRACKER_H
78 inline Scalar maximalCosine()
const;
84 inline Scalar minimalObservationRatio()
const;
92 template <
unsigned int tLowerBoundary>
93 inline unsigned int minimalObservations(
const unsigned int overallObservation)
const;
126 bool stop(
const unsigned int timeout = 0u)
override;
230 bool extractPoses(
const unsigned int lowerFrameIndex,
const unsigned int upperFrameIndex,
OfflinePoses& offlinePoses,
const unsigned int minimalCorrespondences = 5u,
const Geometry::Estimator::EstimatorType estimator =
Geometry::Estimator::ET_SQUARE,
const Scalar minimalValidCorrespondenceRatio =
Scalar(1),
const Scalar ransacMaximalSqrError =
Scalar(3.5 * 3.5),
const Scalar maximalRobustError =
Scalar(3.5 * 3.5),
Scalar* finalAverageError =
nullptr,
Worker* worker =
nullptr,
bool* abort =
nullptr)
const;
253 bool extractPoses(
const unsigned int lowerFrameIndex,
const unsigned int regionOfInterestFrameIndex,
const unsigned int upperFrameIndex,
const CV::SubRegion& regionOfInterest,
OfflinePoses& offlinePoses,
HomogenousMatrix4& planeTransformation,
const unsigned int minimalCorrespondences = 5u,
const unsigned int minimalKeyFrames = 50u,
const Geometry::Estimator::EstimatorType estimator =
Geometry::Estimator::ET_SQUARE,
const Scalar minimalValidCorrespondenceRatio =
Scalar(1),
const Scalar ransacMaximalSqrError =
Scalar(3.5 * 3.5),
const Scalar maximalRobustError =
Scalar(3.5 * 3.5),
Scalar* finalAverageError =
nullptr,
Worker* worker =
nullptr,
bool* abort =
nullptr)
const;
280 static bool determineInitialObjectPoints(
const PinholeCamera& pinholeCamera,
Database& database,
RandomGenerator& randomGenerator,
const unsigned int lowerFrame,
const unsigned int* startFrame,
const unsigned int upperFrame,
const CV::SubRegion& regionOfInterest,
const bool soleRegionOfInterest,
unsigned int* finalLowerValidPoseRange =
nullptr,
unsigned int* finalUpperValidPoseRange =
nullptr,
bool* abort =
nullptr,
Scalar* progress =
nullptr);
320 static bool optimizeCamera(
const PinholeCamera& pinholeCamera,
const Database& database,
const unsigned int lowerFrame,
const unsigned int upperFrame,
const bool findInitialFieldOfView,
const PinholeCamera::OptimizationStrategy optimizationStrategy,
const unsigned int maximalKeyFrames,
PinholeCamera& optimizedCamera,
Database& optimizedDatabase,
Solver3::CameraMotion* cameraMotion =
nullptr,
bool* abort =
nullptr,
Scalar* finalMeanSqrError =
nullptr);
341 static bool extendStableObjectPoints(
const PinholeCamera& pinholeCamera,
Database& database,
RandomGenerator& randomGenerator,
const unsigned int lowerFrame,
const unsigned int upperFrame,
const Solver3::CameraMotion cameraMotion =
Solver3::CM_UNKNOWN,
const Solver3::RelativeThreshold& correspondenceThreshold =
Solver3::RelativeThreshold(10u,
Scalar(0.5), 25u),
unsigned int* finalLowerValidPoseRange =
nullptr,
unsigned int* finalUpperValidPoseRange =
nullptr,
Solver3::CameraMotion* finalCameraMotion =
nullptr,
bool* abort =
nullptr,
Scalar* progress =
nullptr);
365 static bool removeInaccurateObjectPoints(
const PinholeCamera& pinholeCamera,
const Solver3::CameraMotion cameraMotion,
Database& database,
RandomGenerator& randomGenerator,
const unsigned int lowerFrame,
const unsigned int upperFrame,
const unsigned int minimalCorrespondences,
const Scalar minimalValidCorrespondenceRatio =
Scalar(1),
const Scalar maximalAverageSqrError =
Scalar(3.5 * 3.5),
const Scalar maximalWorstSqrError =
Scalar(5.5 * 5.5),
const unsigned int iterations = (
unsigned int)(-1),
unsigned int* finalLowerValidPoseRange =
nullptr,
unsigned int* finalUpperValidPoseRange =
nullptr,
bool* abort =
nullptr);
388 static bool optimizeObjectPointsAndPosesIndividuallyIteratively(
const PinholeCamera& pinholeCamera,
const Solver3::CameraMotion cameraMotion,
Database& database,
RandomGenerator& randomGenerator,
const unsigned int lowerFrame,
const unsigned int upperFrame,
Indices32& objectPointIds,
const unsigned int minimalCorrespondences,
const bool beginWithPoseUpdate,
const unsigned int iterations,
const Geometry::Estimator::EstimatorType estimator,
const Scalar minimalValidCorrespondenceRatio,
const Scalar maximalRobustError,
Scalar* initialAverageError,
Scalar* finalAverageError,
bool* abort);
425 static bool addUnknownObjectPointsInPlanarRegionOfInterest(
const PinholeCamera& pinholeCamera,
Database& database,
RandomGenerator& randomGenerator,
const unsigned int lowerFrame,
const unsigned int regionOfInterestFrame,
const unsigned int upperFrame,
const CV::SubRegion& regionOfInterest,
const Solver3::CameraMotion cameraMotion =
Solver3::CM_UNKNOWN,
const unsigned int minimalObservations = 10u,
Plane3* plane =
nullptr,
bool* abort =
nullptr);
442 static bool determineValidCorrespondencesInPlanarRegionOfInterest(
const PinholeCamera& pinholeCamera,
const Database& database,
const unsigned int lowerFrame,
const unsigned int regionOfInterestFrame,
const unsigned int upperFrame,
const CV::SubRegion& regionOfInterest,
const Plane3& plane,
Indices32* validCorrespondences =
nullptr,
Scalar* meanCorrespondences =
nullptr,
unsigned int* medianCorrespondences =
nullptr,
bool* abort =
nullptr);
459 static bool determineNumberImagePointsInPlanarRegionOfInterest(
const PinholeCamera& pinholeCamera,
const Database& database,
const unsigned int lowerFrame,
const unsigned int regionOfInterestFrame,
const unsigned int upperFrame,
const CV::SubRegion& regionOfInterest,
const Plane3& plane,
Indices32* numberImagePoints =
nullptr,
Scalar* meanNumberImagePoints =
nullptr,
unsigned int* medianNumberImagePoints =
nullptr,
bool* abort =
nullptr);
519 static bool extendStableObjectPointsFull(
const PinholeCamera& pinholeCamera,
Database& database,
const Solver3::CameraMotion cameraMotion,
const unsigned int lowerFrame,
const unsigned int upperFrame,
const Solver3::RelativeThreshold& correspondenceThreshold =
Solver3::RelativeThreshold(10u,
Scalar(0.5), 25u),
unsigned int* finalLowerValidPoseRange =
nullptr,
unsigned int* finalUpperValidPoseRange =
nullptr,
bool* abort =
nullptr,
Scalar* progress =
nullptr);
537 static bool extendStableObjectPointsPartially(
const PinholeCamera& pinholeCamera,
Database& database,
const Solver3::CameraMotion cameraMotion,
const unsigned int lowerFrame,
const unsigned int upperFrame,
const Solver3::RelativeThreshold& correspondenceThreshold =
Solver3::RelativeThreshold(10u,
Scalar(0.5), 25u),
unsigned int* finalLowerValidPoseRange =
nullptr,
unsigned int* finalUpperValidPoseRange =
nullptr,
bool* abort =
nullptr,
Scalar* progress =
nullptr);
555 static bool extendStableObjectPointsFullRotational(
const PinholeCamera& pinholeCamera,
Database& database,
const unsigned int lowerFrame,
const unsigned int upperFrame,
const Solver3::RelativeThreshold& correspondenceThreshold =
Solver3::RelativeThreshold(10u,
Scalar(0.5), 25u),
unsigned int* finalLowerValidPoseRange =
nullptr,
unsigned int* finalUpperValidPoseRange =
nullptr,
bool* abort =
nullptr,
Scalar* progress =
nullptr);
573 static bool extendStableObjectPointsFullTranslational(
const PinholeCamera& pinholeCamera,
Database& database,
const unsigned int lowerFrame,
const unsigned int upperFrame,
const Solver3::RelativeThreshold& correspondenceThreshold =
Solver3::RelativeThreshold(10u,
Scalar(0.5), 25u),
unsigned int* finalLowerValidPoseRange =
nullptr,
unsigned int* finalUpperValidPoseRange =
nullptr,
bool* abort =
nullptr,
Scalar* progress =
nullptr);
592 static bool extendStableObjectPointsPartiallyRotational(
const PinholeCamera& pinholeCamera,
Database& database,
const unsigned int lowerFrame,
const unsigned int upperFrame,
const Solver3::RelativeThreshold& correspondenceThreshold =
Solver3::RelativeThreshold(10u,
Scalar(0.5), 25u),
unsigned int* finalLowerValidPoseRange =
nullptr,
unsigned int* finalUpperValidPoseRange =
nullptr,
bool* abort =
nullptr,
Scalar* progress =
nullptr);
611 static bool stabilizeStableObjectPointsPartiallyTranslational(
const PinholeCamera& pinholeCamera,
Database& database,
const unsigned int lowerFrame,
const unsigned int upperFrame,
const Solver3::RelativeThreshold& correspondenceThreshold =
Solver3::RelativeThreshold(10u,
Scalar(0.5), 25u),
unsigned int* finalLowerValidPoseRange =
nullptr,
unsigned int* finalUpperValidPoseRange =
nullptr,
bool* abort =
nullptr,
Scalar* progress =
nullptr);
632 static bool extendStableObjectPointsPartiallyTranslational(
const PinholeCamera& pinholeCamera,
Database& database,
const unsigned int lowerFrame,
const unsigned int upperFrame,
const Solver3::RelativeThreshold& correspondenceThreshold =
Solver3::RelativeThreshold(10u,
Scalar(0.5), 25u),
unsigned int* finalLowerValidPoseRange =
nullptr,
unsigned int* finalUpperValidPoseRange =
nullptr,
bool* abort =
nullptr,
Scalar* progress =
nullptr);
651 static inline void setProgress(
Scalar* progress,
const Scalar value);
697 bool soleRegionOfInterestApplication_ =
false;
707 maximalCosineValue_(maximalCosine),
708 minimalObservationRatio_(minimalObservationRatio)
716 return maximalCosineValue_;
721 return minimalObservationRatio_;
724 template <
unsigned int tLowerBoundary>
727 return max(min(tLowerBoundary, overallObservation), (
unsigned int)(
Scalar(overallObservation) * minimalObservationRatio_));
737 ocean_assert(value >= 0 && value <= 1);
This class implement a sub-region either defined by 2D triangles or defined by a binary mask.
Definition: SubRegion.h:32
Definition of a frame type composed by the frame dimension, pixel format and pixel origin.
Definition: Frame.h:30
EstimatorType
Definition of individual robust estimator types.
Definition: Estimator.h:34
@ ET_SQUARE
The standard square error estimator (L2).
Definition: Estimator.h:52
OptimizationStrategy
Definition of individual optimization strategies for camera parameters.
Definition: PinholeCamera.h:129
@ OS_INTRINSIC_PARAMETERS_DISTORTIONS
Optimization of all 8 intrinsic camera parameters including the distortion parameters: (2x focal leng...
Definition: PinholeCamera.h:143
This class implements a generator for random numbers.
Definition: RandomGenerator.h:42
This template class implements a smart object reference which is a specialization of an ObjectRef obj...
Definition: SmartObjectRef.h:90
This class implements a database for 3D object points, 2D image points and 6DOF camera poses.
Definition: Database.h:67
This class implements the base class for all visual offline tracker using frames to provide the track...
Definition: FrameTracker.h:46
TrackingQuality
Definition of individual tracking qualities.
Definition: OfflineTracker.h:54
AbstractMotionType
Definition of individual abstract camera motion types.
Definition: OfflineTracker.h:77
MotionSpeed
Definition of individual camera motion speeds.
Definition: PointPaths.h:43
@ MS_MODERATE
A moderate motion of the camera.
Definition: PointPaths.h:47
This class implements a pair of thresholds.
Definition: SLAMTracker.h:64
const Scalar minimalObservationRatio_
The minimal observation ratio.
Definition: SLAMTracker.h:101
Scalar maximalCosine() const
Returns the maximal cosine value.
Definition: SLAMTracker.h:714
const Scalar maximalCosineValue_
The maximal cosine value.
Definition: SLAMTracker.h:98
ReliabilityPair(const Scalar maximalCosine, const Scalar minimalObservationRatio)
Creates a new pair object.
Definition: SLAMTracker.h:706
unsigned int minimalObservations(const unsigned int overallObservation) const
Returns the minimal number of observations in relation to a given number of maximal possible observat...
Definition: SLAMTracker.h:725
Scalar minimalObservationRatio() const
Returns the minimal observation ratio.
Definition: SLAMTracker.h:719
This class implements a SLAM (Simultaneous Localization and Mapping) tracker for arbitrary environmen...
Definition: SLAMTracker.h:50
~SLAMTracker() override
Destructs a SLAM Tracker object.
static bool adjustPosesToCameraWithoutDistortion(const PinholeCamera &oldCamera, const TransformationMap &oldPoses, const PinholeCamera &newCamera, TransformationMap &newPoses, TransformationMap &newObjectTransformations)
Adjusts camera poses specified for a specific camera profile without distortion parameters to a new c...
static bool extendStableObjectPointsFullTranslational(const PinholeCamera &pinholeCamera, Database &database, const unsigned int lowerFrame, const unsigned int upperFrame, const Solver3::RelativeThreshold &correspondenceThreshold=Solver3::RelativeThreshold(10u, Scalar(0.5), 25u), unsigned int *finalLowerValidPoseRange=nullptr, unsigned int *finalUpperValidPoseRange=nullptr, bool *abort=nullptr, Scalar *progress=nullptr)
This function extends a database providing stable/accurate and reliable locations of 3D object points...
virtual AbstractMotionType abstractMotionType() const
Returns the abstract motion type of this tracker.
static bool extendStableObjectPointsPartiallyRotational(const PinholeCamera &pinholeCamera, Database &database, const unsigned int lowerFrame, const unsigned int upperFrame, const Solver3::RelativeThreshold &correspondenceThreshold=Solver3::RelativeThreshold(10u, Scalar(0.5), 25u), unsigned int *finalLowerValidPoseRange=nullptr, unsigned int *finalUpperValidPoseRange=nullptr, bool *abort=nullptr, Scalar *progress=nullptr)
This function extends a database providing stable/accurate and reliable locations of 3D object points...
const CV::SubRegion & regionOfInterest() const
Returns the specific region of interest which covers image content in the start frame of this tracker...
Definition: SLAMTracker.h:730
static void extractObjectPointsWithMostObservations(const Indices32 &objectPointIds, const Vectors3 &objectPoints, const Indices32 &objectPointObservations, const size_t subsetSize, Indices32 &bestObjectPointIds, Vectors3 &bestObjectPoints)
Extracts a subset of object point ids and object points from a large set of object point ids,...
static bool optimizeCamera(const PinholeCamera &pinholeCamera, const Database &database, const unsigned int lowerFrame, const unsigned int upperFrame, const bool findInitialFieldOfView, const PinholeCamera::OptimizationStrategy optimizationStrategy, const unsigned int maximalKeyFrames, PinholeCamera &optimizedCamera, Database &optimizedDatabase, Solver3::CameraMotion *cameraMotion=nullptr, bool *abort=nullptr, Scalar *finalMeanSqrError=nullptr)
Optimizes the camera profile for a database with stable initial object points.
virtual TrackingQuality trackingQuality() const
Returns the tracking quality of this tracker.
static bool determineNumberImagePointsInPlanarRegionOfInterest(const PinholeCamera &pinholeCamera, const Database &database, const unsigned int lowerFrame, const unsigned int regionOfInterestFrame, const unsigned int upperFrame, const CV::SubRegion ®ionOfInterest, const Plane3 &plane, Indices32 *numberImagePoints=nullptr, Scalar *meanNumberImagePoints=nullptr, unsigned int *medianNumberImagePoints=nullptr, bool *abort=nullptr)
Determines the number of visible image points in a planar region of interest for a defined range of f...
virtual bool setCameraOptimizationStrategy(const PinholeCamera::OptimizationStrategy optimizationStrategy)
Sets the optimization strategy for the camera profile of this tracker.
CV::SubRegion regionOfInterest_
The region of interest of this tracker, if any.
Definition: SLAMTracker.h:691
Database database_
The database of this tracker.
Definition: SLAMTracker.h:673
void maintenanceSendEnvironment()
Sends environment information to the maintenance manager.
static bool extendInitialObjectPoints(const PinholeCamera &pinholeCamera, Database &database, const unsigned int lowerFrame, const unsigned int upperFrame, const Solver3::RelativeThreshold &correspondenceThreshold=Solver3::RelativeThreshold(10u, Scalar(0.5), 25u), unsigned int *finalLowerValidPoseRange=nullptr, unsigned int *finalUpperValidPoseRange=nullptr, bool *abort=nullptr)
Determines the locations of further (stable and reliable) 3D object points which are visible within a...
bool extractPoses(const unsigned int lowerFrameIndex, const unsigned int upperFrameIndex, OfflinePoses &offlinePoses, const unsigned int minimalCorrespondences=5u, const Geometry::Estimator::EstimatorType estimator=Geometry::Estimator::ET_SQUARE, const Scalar minimalValidCorrespondenceRatio=Scalar(1), const Scalar ransacMaximalSqrError=Scalar(3.5 *3.5), const Scalar maximalRobustError=Scalar(3.5 *3.5), Scalar *finalAverageError=nullptr, Worker *worker=nullptr, bool *abort=nullptr) const
Extracts the poses from this tracker for a specified frame range not considering any specific region ...
virtual bool setAbstractMotionType(const AbstractMotionType abstractMotionType)
Sets the abstract motion type of this tracker, if known before that tracker starts.
static bool extendStableObjectPoints(const PinholeCamera &pinholeCamera, Database &database, RandomGenerator &randomGenerator, const unsigned int lowerFrame, const unsigned int upperFrame, const Solver3::CameraMotion cameraMotion=Solver3::CM_UNKNOWN, const Solver3::RelativeThreshold &correspondenceThreshold=Solver3::RelativeThreshold(10u, Scalar(0.5), 25u), unsigned int *finalLowerValidPoseRange=nullptr, unsigned int *finalUpperValidPoseRange=nullptr, Solver3::CameraMotion *finalCameraMotion=nullptr, bool *abort=nullptr, Scalar *progress=nullptr)
This function extends a database providing stable/accurate and reliable locations of 3D object points...
static void setProgress(Scalar *progress, const Scalar value)
Sets an optional progress value to a fixed value.
Definition: SLAMTracker.h:735
virtual bool setTrackingQuality(const TrackingQuality trackingQuality)
Sets the tracking quality of the tracker.
SLAMTracker()=default
Creates a new SLAM Tracker object.
virtual PointPaths::MotionSpeed motionSpeed() const
Returns the motion speed of this tracker (the speed of the visual information in the frames on which ...
virtual Scalar cameraFieldOfView() const
Returns the used-defined horizontal field of view of the camera.
static bool extendStableObjectPointsFullRotational(const PinholeCamera &pinholeCamera, Database &database, const unsigned int lowerFrame, const unsigned int upperFrame, const Solver3::RelativeThreshold &correspondenceThreshold=Solver3::RelativeThreshold(10u, Scalar(0.5), 25u), unsigned int *finalLowerValidPoseRange=nullptr, unsigned int *finalUpperValidPoseRange=nullptr, bool *abort=nullptr, Scalar *progress=nullptr)
This function extends a database providing stable/accurate and reliable locations of 3D object points...
static bool extendStableObjectPointsPartiallyTranslational(const PinholeCamera &pinholeCamera, Database &database, const unsigned int lowerFrame, const unsigned int upperFrame, const Solver3::RelativeThreshold &correspondenceThreshold=Solver3::RelativeThreshold(10u, Scalar(0.5), 25u), unsigned int *finalLowerValidPoseRange=nullptr, unsigned int *finalUpperValidPoseRange=nullptr, bool *abort=nullptr, Scalar *progress=nullptr)
This function extends a database providing stable/accurate and reliable locations of 3D object points...
bool start() override
Starts the offline tracker.
static bool removeInaccurateObjectPoints(const PinholeCamera &pinholeCamera, const Solver3::CameraMotion cameraMotion, Database &database, RandomGenerator &randomGenerator, const unsigned int lowerFrame, const unsigned int upperFrame, const unsigned int minimalCorrespondences, const Scalar minimalValidCorrespondenceRatio=Scalar(1), const Scalar maximalAverageSqrError=Scalar(3.5 *3.5), const Scalar maximalWorstSqrError=Scalar(5.5 *5.5), const unsigned int iterations=(unsigned int)(-1), unsigned int *finalLowerValidPoseRange=nullptr, unsigned int *finalUpperValidPoseRange=nullptr, bool *abort=nullptr)
Removes all inaccurate locations of 3D object points from a given database.
static bool extendStableObjectPointsPartially(const PinholeCamera &pinholeCamera, Database &database, const Solver3::CameraMotion cameraMotion, const unsigned int lowerFrame, const unsigned int upperFrame, const Solver3::RelativeThreshold &correspondenceThreshold=Solver3::RelativeThreshold(10u, Scalar(0.5), 25u), unsigned int *finalLowerValidPoseRange=nullptr, unsigned int *finalUpperValidPoseRange=nullptr, bool *abort=nullptr, Scalar *progress=nullptr)
This function extends a database providing stable/accurate and reliable locations of 3D object points...
static bool determineInitialObjectPoints(const PinholeCamera &pinholeCamera, Database &database, RandomGenerator &randomGenerator, const unsigned int lowerFrame, const unsigned int *startFrame, const unsigned int upperFrame, const CV::SubRegion ®ionOfInterest, const bool soleRegionOfInterest, unsigned int *finalLowerValidPoseRange=nullptr, unsigned int *finalUpperValidPoseRange=nullptr, bool *abort=nullptr, Scalar *progress=nullptr)
Determines the location of some initial 3D object points which are all visible within a defined frame...
bool setRegionOfInterest(const CV::SubRegion ®ionOfInterest, const bool soleApplication)
Sets a specific region of interest which covers image content in the start frame of this tracker.
static bool determineValidCorrespondencesInPlanarRegionOfInterest(const PinholeCamera &pinholeCamera, const Database &database, const unsigned int lowerFrame, const unsigned int regionOfInterestFrame, const unsigned int upperFrame, const CV::SubRegion ®ionOfInterest, const Plane3 &plane, Indices32 *validCorrespondences=nullptr, Scalar *meanCorrespondences=nullptr, unsigned int *medianCorrespondences=nullptr, bool *abort=nullptr)
Determines the number of valid correspondences (2D/3D correspondences which are used for pose determi...
std::map< unsigned int, HomogenousMatrix4 > TransformationMap
Definition of a map mapping frame indices to transformations e.g., camera poses or object transformat...
Definition: SLAMTracker.h:56
Scheduler::Callback schedulerCallback_
The callback function that has been registered at the scheduler.
Definition: SLAMTracker.h:703
static bool extendStableObjectPointsFull(const PinholeCamera &pinholeCamera, Database &database, const Solver3::CameraMotion cameraMotion, const unsigned int lowerFrame, const unsigned int upperFrame, const Solver3::RelativeThreshold &correspondenceThreshold=Solver3::RelativeThreshold(10u, Scalar(0.5), 25u), unsigned int *finalLowerValidPoseRange=nullptr, unsigned int *finalUpperValidPoseRange=nullptr, bool *abort=nullptr, Scalar *progress=nullptr)
This function extends a database providing stable/accurate and reliable locations of 3D object points...
static bool adjustPlaneTransformationToRegionOfInterest(const PinholeCamera &pinholeCamera, const HomogenousMatrix4 &pose, const CV::SubRegion ®ionOfInterest, HomogenousMatrix4 &planeTransformation)
Adjusts a transformation of a plane representing the geometry for a region of interest,...
virtual bool setCameraFieldOfView(const Scalar fovX)
Explicitly sets the horizontal field of view of the camera.
static bool adjustPosesAndPlaneToCamera(const PinholeCamera &oldCamera, const OfflinePoses &oldPoses, const HomogenousMatrix4 &oldPlaneTransformation, const unsigned int selectionFrameIndex, const PinholeCamera &newCamera, OfflinePoses &newPoses, HomogenousMatrix4 &newPlaneTransformation, const unsigned int iterations=30u, Scalar *finalError=nullptr)
Adjusts camera poses specified for a specific camera profile (which may include distortion) to a new ...
bool extractPoses(const unsigned int lowerFrameIndex, const unsigned int regionOfInterestFrameIndex, const unsigned int upperFrameIndex, const CV::SubRegion ®ionOfInterest, OfflinePoses &offlinePoses, HomogenousMatrix4 &planeTransformation, const unsigned int minimalCorrespondences=5u, const unsigned int minimalKeyFrames=50u, const Geometry::Estimator::EstimatorType estimator=Geometry::Estimator::ET_SQUARE, const Scalar minimalValidCorrespondenceRatio=Scalar(1), const Scalar ransacMaximalSqrError=Scalar(3.5 *3.5), const Scalar maximalRobustError=Scalar(3.5 *3.5), Scalar *finalAverageError=nullptr, Worker *worker=nullptr, bool *abort=nullptr) const
Extracts the poses from this tracker for a specific region of interest.
static bool stabilizeStableObjectPointsPartiallyTranslational(const PinholeCamera &pinholeCamera, Database &database, const unsigned int lowerFrame, const unsigned int upperFrame, const Solver3::RelativeThreshold &correspondenceThreshold=Solver3::RelativeThreshold(10u, Scalar(0.5), 25u), unsigned int *finalLowerValidPoseRange=nullptr, unsigned int *finalUpperValidPoseRange=nullptr, bool *abort=nullptr, Scalar *progress=nullptr)
This function stabilizes a database already providing stable/accurate and reliable locations of 3D ob...
static bool optimizeObjectPointsAndPosesIndividuallyIteratively(const PinholeCamera &pinholeCamera, const Solver3::CameraMotion cameraMotion, Database &database, RandomGenerator &randomGenerator, const unsigned int lowerFrame, const unsigned int upperFrame, Indices32 &objectPointIds, const unsigned int minimalCorrespondences, const bool beginWithPoseUpdate, const unsigned int iterations, const Geometry::Estimator::EstimatorType estimator, const Scalar minimalValidCorrespondenceRatio, const Scalar maximalRobustError, Scalar *initialAverageError, Scalar *finalAverageError, bool *abort)
Optimizes a set of given 3D object point locations and all camera poses within a specified frame rang...
virtual bool setMotionSpeed(const PointPaths::MotionSpeed motionSpeed)
Sets the motion speed of this tracker.
void onScheduler()
The event function for the scheduler.
virtual PinholeCamera::OptimizationStrategy cameraOptimizationStrategy() const
Returns the camera profile optimization strategy of this tracker.
static bool addUnknownObjectPointsInPlanarRegionOfInterest(const PinholeCamera &pinholeCamera, Database &database, RandomGenerator &randomGenerator, const unsigned int lowerFrame, const unsigned int regionOfInterestFrame, const unsigned int upperFrame, const CV::SubRegion ®ionOfInterest, const Solver3::CameraMotion cameraMotion=Solver3::CM_UNKNOWN, const unsigned int minimalObservations=10u, Plane3 *plane=nullptr, bool *abort=nullptr)
This functions extends an already reliable database with precise 3D object point locations and camera...
bool stop(const unsigned int timeout=0u) override
Stops the offline tracker.
bool applyFrameTracking(const FrameType &frameType) override
Frame tracker run function.
static bool addUnknownObjectPointsInRegionOfInterest(const PinholeCamera &pinholeCamera, Database &database, RandomGenerator &randomGenerator, const unsigned int lowerFrame, const unsigned int regionOfInterestFrame, const unsigned int upperFrame, const CV::SubRegion ®ionOfInterest, const Solver3::CameraMotion cameraMotion=Solver3::CM_UNKNOWN, const unsigned int minimalObservations=10u, bool *abort=nullptr)
This functions extends an already reliable database with precise 3D object point locations and camera...
Definition of a class allowing to define a relative threshold with lower and upper boundary for indiv...
Definition: Solver3.h:93
CameraMotion
Definition of individual camera motion types.
Definition: Solver3.h:49
@ CM_INVALID
Invalid camera motion.
Definition: Solver3.h:51
@ CM_UNKNOWN
An unknown (arbitrary) camera motion with rotational and translational motion.
Definition: Solver3.h:71
This class implements a worker able to distribute function calls over different threads.
Definition: Worker.h:33
std::vector< Index32 > Indices32
Definition of a vector holding 32 bit index values.
Definition: Base.h:96
float Scalar
Definition of a scalar type.
Definition: Math.h:128
std::vector< Vector3 > Vectors3
Definition of a vector holding Vector3 objects.
Definition: Vector3.h:65
SmartObjectRef< SLAMTracker, OfflineTracker > SLAMTrackerRef
Definition of an object reference holding a PlanarRectangleTracker object.
Definition: SLAMTracker.h:33
The namespace covering the entire Ocean framework.
Definition: Accessor.h:15