NASA Astrobee Robot Software  0.19.1
Flight software for the Astrobee robots operating inside the International Space Station.
reprojection.h File Reference
#include <Eigen/Geometry>
#include <ff_common/eigen_vectors.h>
#include <ceres/ceres.h>
#include <map>
#include <vector>
#include <limits>
#include <string>
#include <set>
Include dependency graph for reprojection.h:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Classes

class  cv::Point_< T >
 
class  cv::Point3_< T >
 

Namespaces

 camera
 
 cv
 
 sparse_mapping
 

Typedefs

typedef Point_< double > cv::Point2d
 
typedef Point3_< double > cv::Point3d
 

Functions

ceres::LossFunction * sparse_mapping::GetLossFunction (std::string cost_fun, double th)
 
void sparse_mapping::BundleAdjust (std::vector< std::map< int, int > > const &pid_to_cid_fid, std::vector< Eigen::Matrix2Xd > const &cid_to_keypoint_map, double focal_length, std::vector< Eigen::Affine3d > *cid_to_cam_t_global, std::vector< Eigen::Vector3d > *pid_to_xyz, std::vector< std::map< int, int > > const &user_pid_to_cid_fid, std::vector< Eigen::Matrix2Xd > const &user_cid_to_keypoint_map, std::vector< Eigen::Vector3d > *user_pid_to_xyz, ceres::LossFunction *loss, ceres::Solver::Options const &options, ceres::Solver::Summary *summary, int first=0, int last=std::numeric_limits< int >::max(), bool fix_cameras=false, std::set< int > const &fixed_cameras=std::set< int >())
 
void sparse_mapping::BundleAdjustSmallSet (std::vector< Eigen::Matrix2Xd > const &features_n, double focal_length, std::vector< Eigen::Affine3d > *cam_t_global_n, Eigen::Matrix3Xd *pid_to_xyz, ceres::LossFunction *loss, ceres::Solver::Options const &options, ceres::Solver::Summary *summary)
 
int sparse_mapping::RandomInt (int min, int max)
 
void sparse_mapping::SelectRandomObservations (const std::vector< Eigen::Vector3d > &all_landmarks, const std::vector< Eigen::Vector2d > &all_observations, size_t num_selected, std::vector< cv::Point3d > *landmarks, std::vector< cv::Point2d > *observations)
 
size_t sparse_mapping::CountInliers (const std::vector< Eigen::Vector3d > &landmarks, const std::vector< Eigen::Vector2d > &observations, const camera::CameraModel &camera, int tolerance, std::vector< size_t > *inliers)
 
void sparse_mapping::EstimateCamera (camera::CameraModel *camera_estimate, std::vector< Eigen::Vector3d > *landmarks, const std::vector< Eigen::Vector2d > &observations, const ceres::Solver::Options &options, ceres::Solver::Summary *summary)
 
int sparse_mapping::RansacEstimateCamera (const std::vector< Eigen::Vector3d > &landmarks, const std::vector< Eigen::Vector2d > &observations, int num_tries, int inlier_tolerance, camera::CameraModel *camera_estimate, std::vector< Eigen::Vector3d > *inlier_landmarks_out=NULL, std::vector< Eigen::Vector2d > *inlier_observations_out=NULL, bool verbose=false)
 
void sparse_mapping::Find3DAffineTransform (Eigen::Matrix3Xd const &in, Eigen::Matrix3Xd const &out, Eigen::Affine3d *result)