![]() |
NASA Astrobee Robot Software
0.19.1
Flight software for the Astrobee robots operating inside the International Space Station.
|
#include <ff_common/eigen_vectors.h>#include <localization_common/logger.h>#include <localization_common/pose_with_covariance.h>#include <localization_common/utilities.h>#include <optimization_common/residuals.h>#include <optimization_common/utilities.h>#include <vision_common/pose_with_covariance_and_inliers.h>#include <vision_common/ransac_pnp_params.h>#include <vision_common/reprojection_pose_estimate_params.h>#include <vision_common/utilities.h>#include <Eigen/Geometry>#include <ceres/ceres.h>#include <ceres/solver.h>#include <opencv2/calib3d/calib3d.hpp>#include <opencv2/core/eigen.hpp>#include <opencv2/imgcodecs.hpp>#include <opencv2/imgproc.hpp>#include <opencv2/opencv.hpp>#include <boost/optional.hpp>#include <algorithm>#include <string>#include <unordered_set>#include <utility>#include <vector>

Go to the source code of this file.
Namespaces | |
| vision_common | |
Functions | |
| void | vision_common::UndistortedPnP (const std::vector< cv::Point2d > &undistorted_image_points, const std::vector< cv::Point3d > &points_3d, const cv::Mat &intrinsics, const int pnp_method, cv::Mat &rotation, cv::Mat &translation) |
| std::vector< int > | vision_common::RandomNIndices (const int num_possible_indices, const int num_sampled_indices) |
| template<typename DISTORTER > | |
| int | vision_common::Inliers (const std::vector< Eigen::Vector2d > &image_points, const std::vector< Eigen::Vector3d > &points_3d, const Eigen::Matrix3d &intrinsics, const Eigen::VectorXd &distortion, const Eigen::Isometry3d &pose_estimate, const double max_inlier_threshold, boost::optional< std::vector< int > & > inliers=boost::none) |
| template<typename T > | |
| std::vector< T > | vision_common::SampledValues (const std::vector< T > &values, const std::vector< int > &indices) |
| template<typename DISTORTER > | |
| boost::optional< PoseWithCovarianceAndInliers > | vision_common::RansacPnP (const std::vector< Eigen::Vector2d > &image_points, const std::vector< Eigen::Vector3d > &points_3d, const Eigen::Matrix3d &intrinsics, const Eigen::VectorXd &distortion, const RansacPnPParams ¶ms) |
| template<typename DISTORTER > | |
| boost::optional< PoseWithCovarianceAndInliers > | vision_common::ReprojectionPoseEstimate (const std::vector< Eigen::Vector2d > &image_points, const std::vector< Eigen::Vector3d > &points_3d, const Eigen::Vector2d &focal_lengths, const Eigen::Vector2d &principal_points, const Eigen::VectorXd &distortion, const ReprojectionPoseEstimateParams ¶ms) |
| template<typename DISTORTER > | |
| boost::optional< PoseWithCovarianceAndInliers > | vision_common::ReprojectionPoseEstimate (const std::vector< Eigen::Vector2d > &image_points, const std::vector< Eigen::Vector3d > &points_3d, const Eigen::Matrix3d &intrinsics, const Eigen::VectorXd &distortion, const ReprojectionPoseEstimateParams ¶ms) |
| template<typename DISTORTER > | |
| boost::optional< PoseWithCovarianceAndInliers > | vision_common::ReprojectionPoseEstimateWithInitialEstimate (const std::vector< Eigen::Vector2d > &image_points, const std::vector< Eigen::Vector3d > &points_3d, const Eigen::Vector2d &focal_lengths, const Eigen::Vector2d &principal_points, const Eigen::VectorXd &distortion, const ReprojectionPoseEstimateParams ¶ms, const Eigen::Isometry3d &initial_estimate, const std::vector< int > &initial_inliers) |
| template<typename DISTORTER > | |
| boost::optional< PoseWithCovarianceAndInliers > | vision_common::ReprojectionPoseEstimateWithInitialEstimate (const std::vector< Eigen::Vector2d > &image_points, const std::vector< Eigen::Vector3d > &points_3d, const Eigen::Matrix3d &intrinsics, const Eigen::VectorXd &distortion, const ReprojectionPoseEstimateParams ¶ms, const Eigen::Isometry3d &initial_estimate, const std::vector< int > &initial_inliers) |