VSLAM class that performs visual odometry, loop closure through place recognition, and large-scale optimization using SBA. More...
#include <vslam.h>

Public Member Functions | |
| bool | addFrame (const frame_common::CamParams &camera_parameters, const cv::Mat &left, const cv::Mat &right, const pcl::PointCloud< pcl::PointXYZRGB > &ptcloud, int nfrac=0) |
| Add a frame to the system. | |
| bool | addFrame (const frame_common::CamParams &camera_parameters, const cv::Mat &left, const cv::Mat &right, int nfrac=0, bool setPointCloud=false) |
| Add a frame to the system. | |
| void | addKeyframe (frame_common::Frame &next_frame) |
| void | refine (int initial_runs=3) |
| Perform a refinement on the large-scale SBA system. | |
| void | setHuber (double x) |
| Set the window size for place recognition matching. | |
| void | setKeyAngle (double n) |
| Set minimum keyframe distance in meters. | |
| void | setKeyDist (double n) |
| Set keyframe inliers. | |
| void | setKeyInliers (int n) |
| Set number of keyframes to skip for Place Recognition. | |
| void | setNDisp (int n) |
| Set minimum keyframe angle in radians. | |
| void | setPlaceInliers (int n) |
| void | setPointcloudProc (boost::shared_ptr< frame_common::PointcloudProc > proc) |
| Set the pointcloud processor. | |
| void | setPRPolish (bool n) |
| Set the number of RANSAC iterations for place recognition pose estimate. | |
| void | setPRRansacIt (int n) |
| Set the number of disparities in stereo processing. | |
| void | setPRSkip (int n) |
| Place recognition inliers. | |
| void | setPRWindow (int x, int y) |
| Set whether to polish pose estimate for visual odometry using SBA. | |
| void | setVOPolish (bool n) |
| Set the number of RANSAC iterations for visual odometry pose estimate. | |
| void | setVORansacIt (int n) |
| Set whether to polish the place recognition pose estimate using SBA. | |
| void | setVOWindow (int x, int y) |
| Set the window size for place recognition matching. | |
| VslamSystem (const std::string &vocab_tree_file, const std::string &vocab_weights_file, int min_keyframe_inliers=0, double min_keyframe_distance=0.2, double min_keyframe_angle=0.1) | |
| Constructor for VslamSystem. | |
Public Attributes | |
| bool | doPointPlane |
| frame_common::FrameProc | frame_processor_ |
| std::vector < frame_common::Frame, Eigen::aligned_allocator < frame_common::Frame > > | frames_ |
| Image frames in system. | |
| int | nSkip |
| Number of the most recent frames to skip for PR checking. | |
| int | numPRs |
| Number of place recognitions that succeeded. | |
| vslam::PlaceRecognizer | place_recognizer_ |
| Place recognizer. | |
| std::vector< cv::DMatch > | pointcloud_matches_ |
| Pointcloud matches. | |
| boost::shared_ptr < frame_common::PointcloudProc > | pointcloud_processor_ |
| Pointer to pointcloud processor. | |
| pe::PoseEstimator3d | pose_estimator_ |
| For place recognition matches. | |
| int | prInliers |
| Number of inliers needed for PR match. | |
| sba::SysSBA | sba_ |
| Large-scale SBA system. | |
| vslam::voSt | vo_ |
| Visual odometry processor. | |
VSLAM class that performs visual odometry, loop closure through place recognition, and large-scale optimization using SBA.
Definition at line 12 of file vslam.h.
| vslam::VslamSystem::VslamSystem | ( | const std::string & | vocab_tree_file, | |
| const std::string & | vocab_weights_file, | |||
| int | min_keyframe_inliers = 0, |
|||
| double | min_keyframe_distance = 0.2, |
|||
| double | min_keyframe_angle = 0.1 | |||
| ) |
Constructor for VslamSystem.
| vocab_tree_file | Path to the vocabulary tree file. | |
| vocab_weights_file | Path to the vocabulary tree weights file. | |
| min_keyframe_distance | Minimum distance between keyframes, in meters. | |
| min_keyframe_angle | Minimum angle between keyframes, in radians. | |
| min_keyframe_inliers | Minimum inliers in keyframes. |
| bool vslam::VslamSystem::addFrame | ( | const frame_common::CamParams & | camera_parameters, | |
| const cv::Mat & | left, | |||
| const cv::Mat & | right, | |||
| const pcl::PointCloud< pcl::PointXYZRGB > & | ptcloud, | |||
| int | nfrac = 0 | |||
| ) |
Add a frame to the system.
| camera_parameters | Camera parameters for the cameras. | |
| left | Left image. | |
| right | Right image. | |
| ptcloud | Pointcloud to add to the frame. | |
| nfrac | Fractional disparity. If above 0, then right is an int16_t disparity image. |
| bool vslam::VslamSystem::addFrame | ( | const frame_common::CamParams & | camera_parameters, | |
| const cv::Mat & | left, | |||
| const cv::Mat & | right, | |||
| int | nfrac = 0, |
|||
| bool | setPointCloud = false | |||
| ) |
Add a frame to the system.
| camera_parameters | Camera parameters for the cameras. | |
| left | Left image. | |
| right | Right image. | |
| nfrac | Fractional disparity. If above 0, then right is an int16_t disparity image. | |
| setPointCloud. | True if point cloud is to be set up from disparities |
| void vslam::VslamSystem::addKeyframe | ( | frame_common::Frame & | next_frame | ) |
| void vslam::VslamSystem::refine | ( | int | initial_runs = 3 |
) |
| void vslam::VslamSystem::setHuber | ( | double | x | ) | [inline] |
| void vslam::VslamSystem::setKeyAngle | ( | double | n | ) | [inline] |
| void vslam::VslamSystem::setKeyDist | ( | double | n | ) | [inline] |
| void vslam::VslamSystem::setKeyInliers | ( | int | n | ) | [inline] |
| void vslam::VslamSystem::setNDisp | ( | int | n | ) | [inline] |
| void vslam::VslamSystem::setPointcloudProc | ( | boost::shared_ptr< frame_common::PointcloudProc > | proc | ) | [inline] |
| void vslam::VslamSystem::setPRPolish | ( | bool | n | ) | [inline] |
| void vslam::VslamSystem::setPRRansacIt | ( | int | n | ) | [inline] |
| void vslam::VslamSystem::setPRSkip | ( | int | n | ) | [inline] |
| void vslam::VslamSystem::setPRWindow | ( | int | x, | |
| int | y | |||
| ) | [inline] |
| void vslam::VslamSystem::setVOPolish | ( | bool | n | ) | [inline] |
| void vslam::VslamSystem::setVORansacIt | ( | int | n | ) | [inline] |
| void vslam::VslamSystem::setVOWindow | ( | int | x, | |
| int | y | |||
| ) | [inline] |
| frame_common::FrameProc vslam::VslamSystem::frame_processor_ |
| std::vector<frame_common::Frame, Eigen::aligned_allocator<frame_common::Frame> > vslam::VslamSystem::frames_ |
| std::vector<cv::DMatch> vslam::VslamSystem::pointcloud_matches_ |
| boost::shared_ptr<frame_common::PointcloudProc> vslam::VslamSystem::pointcloud_processor_ |
| pe::PoseEstimator3d vslam::VslamSystem::pose_estimator_ |
| sba::SysSBA vslam::VslamSystem::sba_ |