|
| class | ACustomFeatureDetector |
| | Class for custom feature detection and computation. More...
|
| |
| class | ADataProvider |
| | ADataProvider class for managing data from various sensors. More...
|
| |
| class | AFeature |
| | Abstract class for 2D features. More...
|
| |
| class | AFeatureDetector |
| | Abstract class for feature detectors. More...
|
| |
| class | AFeatureMatcher |
| | Class for matching features between two sets of features. More...
|
| |
| class | AFeatureTracker |
| | Implements feature tracking between two images. More...
|
| |
| class | ALandmark |
| | Abstract class for 3D Landmarks. More...
|
| |
| class | ALandmarkInitializer |
| | Abstract class for initializing landmarks. More...
|
| |
| class | AMap |
| | Abstract class for a Map. More...
|
| |
| class | AModel3d |
| | Abstract class for 3D models. More...
|
| |
| class | AngularAdjustmentCERESAnalytic |
| | An optimizer that uses Angular Cost function on the unit sphere for Bundle Adjustment and analytical jacobian derivation. More...
|
| |
| class | AngularErrCeres_linexd_dx |
| | An angular cost function for line landmarks that depends on the delta update of the frame pose and the line parameters. More...
|
| |
| class | AngularErrCeres_pointxd_depth |
| | An angular cost function that depends on the depth of the landmark, the current frame pose and the anchor frame pose. More...
|
| |
| class | AngularErrCeres_pointxd_dx |
| | Angular error cost function for a point landmark in the sensor frame. Parameters are delta update of the frame pose and the landmark position. More...
|
| |
| class | AngularErrorScaleCam0 |
| | An angular cost function that depends on the scale of the motion. More...
|
| |
| class | AngularErrorScaleDepth |
| | An angular cost function that depends on the depth of the landmark and the scale of the motion. More...
|
| |
| class | AOpenCVFeatureDetector |
| | AOpenCVFeatureDetector class for detecting and computing features using OpenCV. More...
|
| |
| class | AOptimizer |
| | Abstract class for optimization pipeline based on CERES. More...
|
| |
| class | APoseEstimator |
| | Abstract class for relative pose estimation between two frames. More...
|
| |
| class | ASensor |
| | Abstract class for all sensors. More...
|
| |
| class | AssociationTest |
| |
| class | BBox2D |
| | A 2D bounding box feature class. More...
|
| |
| class | BBox3D |
| | A 3D bounding box landmark class. More...
|
| |
| class | BundleAdjustmentCERESAnalytic |
| | An optimizer that uses Angular Cost function on the unit sphere for Bundle Adjustment and analytical jacobian derivation. More...
|
| |
| class | BundleAdjustmentCERESNumeric |
| | An optimizer that uses Numeric Cost function for Bundle Adjustment. More...
|
| |
| struct | cam_config |
| | Camera configuration. More...
|
| |
| class | Camera |
| | A pinhole camera sensor class. More...
|
| |
| struct | Config |
| | This structure contains the configuration parameters located in the config file. More...
|
| |
| class | CsvKeypointDetector |
| | This Class is design for CSV reading features. More...
|
| |
| class | cvBRISKFeatureDetector |
| | Class for detecting and computing BRISK features using OpenCV. More...
|
| |
| class | cvFASTFeatureDetector |
| | Class for detecting and computing FAST features using OpenCV. More...
|
| |
| class | cvGFTTFeatureDetector |
| | Class for detecting and computing GFTT (Good Features To Track) features using OpenCV. More...
|
| |
| class | cvKAZEFeatureDetector |
| | Class for detecting and computing KAZE features using OpenCV. More...
|
| |
| class | cvORBFeatureDetector |
| | Class for detecting and computing ORB features using OpenCV. More...
|
| |
| class | DoubleSphere |
| | An image sensor class that uses a double sphere model. More...
|
| |
| class | EpipolarPoseEstimator |
| | EpipolarPoseEstimator class for estimating the pose between two frames using Essential Matrix. More...
|
| |
| class | ESKFEstimator |
| | ESKFEstimator class for estimating the transformation between two frames using an EKF. More...
|
| |
| class | EUROCGrabber |
| | EUROCGrabber class for loading and processing frames from raw data in the EUROC format. More...
|
| |
| struct | FeatureMatcherStruct |
| | A struct that contains a feature matcher and its parameters. More...
|
| |
| struct | FeatureStruct |
| | A struct that gathers all the parameters for a feature. More...
|
| |
| struct | FeatureTrackerStruct |
| | A struct that contains a feature tracker and its parameters. More...
|
| |
| class | Fisheye |
| | An image sensor class that uses the normalized spherical model. More...
|
| |
| class | Frame |
| | A Frame class representing a set of sensors and landmarks at a specific timestamp. More...
|
| |
| class | GlobalMap |
| | Class for a Global Map. More...
|
| |
| class | ImageSensor |
| | Abstract class for image sensors. More...
|
| |
| class | IMU |
| | An Inertial Measurement Unit (IMU) sensor class. More...
|
| |
| struct | imu_config |
| | Config strucuture for an IMU. More...
|
| |
| class | IMUBiasFactor |
| | IMU bias cost function that takes into account random walk behaviour. More...
|
| |
| class | IMUFactor |
| | A cost function for IMU pre-integration factor, parameters are delta updates. More...
|
| |
| class | IMUFactorInit |
| | Pre integration IMU factor for initialization, the parameters optimized are: scale, roll, pitch, velocities and biases. More...
|
| |
| class | IMUFactorInitBis |
| | An experimental IMU factor refining only roll, pitch, biases and scale. More...
|
| |
| class | IMUPriordx |
| | An absolute prior on an Inertial state, including pose, velocity and biases. More...
|
| |
| class | ImuTest |
| |
| class | Landmark3DPrior |
| | A factor for absolute 3D position constraint on a punctual landmark. More...
|
| |
| class | LandmarkToLandmarkFactor |
| | 3D relative translation factor between 3D punctual landmarks More...
|
| |
| class | Line2D |
| | A 2D line feature class. More...
|
| |
| class | Line2DFeatureDetector |
| |
| class | Line2DFeatureMatcher |
| | Class for matching 2D line features. More...
|
| |
| class | Line2DFeatureTracker |
| | Class for tracking 2D line features. More...
|
| |
| class | Line3D |
| | A 3D Line landmark class. More...
|
| |
| class | Line3DLandmarkInitializer |
| | Class for initializing 3D line landmarks. More...
|
| |
| class | LineFeatureTest |
| |
| class | LocalMap |
| | Class for a Local Map. More...
|
| |
| class | Marginalization |
| | Marginalization class that handles marginalization (and sparsification) for fixed-lag smoothing. More...
|
| |
| struct | MarginalizationBlockInfo |
| | Marginalization block struct that stores a factor and the indices of the variables involved. More...
|
| |
| class | MarginalizationFactor |
| | Ceres cost function of the dense prior factor. More...
|
| |
| class | MarginalizationTest |
| |
| class | Mesh3D |
| | A class to build and update a 3D mesh from 2D features and landmarks. More...
|
| |
| class | Mesher |
| | A class to handles 3D meshing via 2D triangulation on successive KFs. More...
|
| |
| class | MeshTest |
| |
| class | ModelBBox3D |
| | Model for a 3D Bounding Box. More...
|
| |
| class | ModelLine3D |
| | Model for a 3D Line. More...
|
| |
| class | ModelPoint3D |
| | Model for a 3D point. More...
|
| |
| class | Motion2DFactor |
| | A cost function to impose a constraint on 2D motion. More...
|
| |
| class | NoFOVTest |
| |
| class | Omni |
| | An image sensor class that uses the Omni model. More...
|
| |
| class | PnPPoseEstimator |
| | PnPPoseEstimator class for estimating the transformation between two frames using PnP. More...
|
| |
| class | Point2D |
| | A single 2D point feature class. More...
|
| |
| class | Point2DFeatureMatcher |
| | Class for matching 2D point features. More...
|
| |
| class | Point2DFeatureTracker |
| | Class for tracking 2D point features. More...
|
| |
| class | Point3D |
| | A 3D Point landmark class. More...
|
| |
| class | Point3DLandmarkInitializer |
| | Class for initializing 3D point landmarks. More...
|
| |
| class | PointXYZParametersBlock |
| | A Parameter block for 3D position that does the interface between a double* and an Eigen::Vector3d. More...
|
| |
| struct | Polygon |
| | A polygon in the 3D mesh, representing a surface with its vertices, normal, barycenter, and covariance. More...
|
| |
| class | PoseParametersBlock |
| | A Parameter block for pose that does the interface between a double* and an Eigen::Affine3d. More...
|
| |
| class | PosePriordx |
| | Absolute 6DoF pose prior factor. More...
|
| |
| class | PoseToLandmarkFactor |
| | Relative 3D translation between a 6DoF frame and a punctual landmark. More...
|
| |
| class | Relative6DPose |
| | A cost function for 6DoF relative pose constraint, the parameters are the delta pose of the two related poses. More...
|
| |
| class | ReprojectionErrCeres_linexd_dx |
| | Reprojection error cost function for a line landmark. The parameters are the delta update of the frame and the delta update of the line 3D parametrization. More...
|
| |
| class | ReprojectionErrCeres_pointxd_dx |
| | Reprojection errro cost function for a punctual landmark. The parameters are the delta update of the frame and the delta update of the 3D position of the landmark. More...
|
| |
| class | ResidualTest |
| |
| class | scalePrior |
| | Prior on a 1D parameter (e.g. scale) More...
|
| |
| class | semanticBBoxFeatureDetector |
| |
| class | semanticBBoxFeatureMatcher |
| | Class for matching 2D bouding box features. More...
|
| |
| class | semanticBBoxFeatureTracker |
| | Class for tracking 2D bounding boxes features. More...
|
| |
| class | semanticBBoxLandmarkInitializer |
| | Class for initializing semantic bounding box landmarks. More...
|
| |
| struct | sensor_config |
| | Abstract struct of a sensor. More...
|
| |
| class | SLAMBiMono |
| | A SLAM class for bi-monocular setups. More...
|
| |
| class | SLAMBiMonoVIO |
| | A SLAM class for bi-monocular + IMU setups. More...
|
| |
| class | SLAMCore |
| | The core abstract class of the SLAM system. It handles front-end, back-end and initialization. More...
|
| |
| class | SLAMMono |
| | A SLAM class for monocular setups. More...
|
| |
| class | SLAMMonoVIO |
| | A SLAM class for monocular + IMU setups. More...
|
| |
| class | SLAMNonOverlappingFov |
| | A SLAM class for non overlapping FoV setups. More...
|
| |
| class | SLAMParameters |
| | A class that gathers most of the algorithmic blocks of the SLAM system that can be setup in the config file. More...
|
| |
| struct | Vertex |
| | A vertex in the 3D mesh, representing a landmark and its associated polygons. More...
|
| |
|
| std::vector< Eigen::Vector3d > | sampleTriangle (std::vector< Eigen::Vector3d > triangle) |
| |
| bool | estimateMotionWithHomography (std::vector< cv::Point2d > p_prev, std::vector< cv::Point2d > p_curr, cv::Mat K, cv::Mat H, std::vector< cv::Mat > Rs, std::vector< cv::Mat > ts, std::vector< cv::Mat > normals, std::vector< int > inliers) |
| |
| Eigen::MatrixXd | jac_homogeneous (const Eigen::Vector3d &point) |
| |
| Eigen::MatrixXd | jac_delta_update (const Eigen::Vector3d &dtheta, const Eigen::Matrix3d &rotation) |
| |
| std::tuple< Eigen::Vector2d, Eigen::MatrixXd, Eigen::MatrixXd > | jac_projection (const Eigen::Matrix3d &camera_matrix, const Eigen::Vector3d &point_3d, const Eigen::Matrix3d &rotation, const Eigen::Vector3d &translation, const Eigen::Vector3d &dtheta) |
| |
| void | subPixelRef (cv::Mat I, std::vector< cv::KeyPoint > &keypoints) |
| |
| Eigen::Affine3d | pose_from_line (std::string line) |
| |
| | TEST_F (AssociationTest, matchLmk) |
| |
| | TEST_F (AssociationTest, epiTest) |
| |
| void | read_line_euroc (std::string line, Eigen::Affine3d &pose, Eigen::Vector3d &v, double &ts) |
| |
| void | write_result (std::shared_ptr< Frame > f) |
| |
| void | write_imu_data (double ts, Eigen::Vector3d acc) |
| |
| | TEST_F (ImuTest, ImuTestBase) |
| |
| | TEST_F (ImuTest, ImuNewMeas) |
| |
| | TEST_F (ImuTest, checkCov) |
| |
| | TEST_F (ImuTest, accelerating) |
| |
| | TEST_F (ImuTest, checkJacobiansBiasGyr) |
| |
| | TEST_F (ImuTest, predictionPositionVelocity) |
| |
| | TEST_F (ImuTest, biasEstimation) |
| |
| | TEST_F (ImuTest, predictionWithRotation) |
| |
| | TEST_F (ImuTest, predictionWithRotation2) |
| |
| | TEST_F (ImuTest, simuEuroc) |
| |
| | TEST_F (ImuTest, TestPreInteg) |
| |
| | TEST_F (LineFeatureTest, LineFeatureRay) |
| |
| | TEST_F (LineFeatureTest, LineFeatureTriangulation) |
| |
| | TEST_F (LineFeatureTest, LineFeatureDetection) |
| |
| | TEST_F (LineFeatureTest, LineFeatureMatching) |
| |
| | TEST_F (MarginalizationTest, setupTest) |
| |
| | TEST_F (MarginalizationTest, preMargTest) |
| |
| | TEST_F (MarginalizationTest, margTest) |
| |
| | TEST_F (MarginalizationTest, margFailTest) |
| |
| | TEST_F (MeshTest, MeshTestBase) |
| |
| | TEST_F (MeshTest, pointInTriangleTest) |
| |
| | TEST_F (MeshTest, covTest) |
| |
| | TEST_F (NoFOVTest, scaleTest) |
| |
| | TEST_F (NoFOVTest, degenerativeCase) |
| |
| | TEST_F (ResidualTest, PriorResidual) |
| |
| | TEST_F (ResidualTest, reprojTest) |
| |
| | TEST_F (ResidualTest, angularTest) |
| |
| | TEST_F (ResidualTest, scaleTest) |
| |
| | TEST_F (ResidualTest, PoseToLandmarkResidual) |
| |
| | TEST_F (ResidualTest, RelativePose6DResidual) |
| |
| | TEST_F (ResidualTest, ESKFLmkTest) |
| |