NASA Astrobee Robot Software
0.19.1
Flight software for the Astrobee robots operating inside the International Space Station.
|
Classes | |
class | CameraTargetBasedIntrinsicsCalibrator |
struct | CameraTargetBasedIntrinsicsCalibratorParams |
struct | MatchSet |
struct | OptimizationStateParameters |
struct | RunCalibratorParams |
struct | StateParameters |
struct | StateParametersCovariances |
Functions | |
void | LoadRunCalibratorParams (config_reader::ConfigReader &config, RunCalibratorParams ¶ms) |
void | LoadCameraTargetBasedIntrinsicsCalibratorParams (config_reader::ConfigReader &config, CameraTargetBasedIntrinsicsCalibratorParams ¶ms) |
void | LoadReprojectionPoseEstimateParams (config_reader::ConfigReader &config, vision_common::ReprojectionPoseEstimateParams ¶ms) |
void | LoadOptimizationParams (config_reader::ConfigReader &config, optimization_common::OptimizationParams ¶ms, const std::string &prefix="") |
void | LoadSolverOptions (config_reader::ConfigReader &config, ceres::Solver::Options &solver_options, const std::string &prefix="") |
void | LoadRansacPnPParams (config_reader::ConfigReader &config, vision_common::RansacPnPParams ¶ms) |
void | PrintCameraTTargetsStats (const std::vector< MatchSet > &match_sets, const std::vector< Eigen::Isometry3d > &optimized_camera_T_targets) |
template<typename DISTORTER > | |
void | SaveReprojectionImage (const std::vector< Eigen::Vector2d > &image_points, const std::vector< Eigen::Vector3d > &points_3d, const std::vector< int > &indices, const Eigen::Matrix3d &intrinsics, const Eigen::VectorXd &distortion, const Eigen::Isometry3d &pose, const double max_visualization_error_norm, const std::string &name) |
template<typename DISTORTER > | |
void | SaveReprojectionFromAllTargetsImage (const std::vector< Eigen::Isometry3d > &camera_T_targets, const std::vector< localization_common::ImageCorrespondences > &valid_match_sets, const Eigen::Matrix3d &intrinsics, const Eigen::VectorXd &distortion, const Eigen::Vector2i &image_size, const double max_visualization_error_norm=100) |
int | ErrorColor (const double error, const double max_error, const double max_color_value) |
cv::Mat | MapImageColors (const cv::Mat &gray_image) |
int calibration::ErrorColor | ( | const double | error, |
const double | max_error, | ||
const double | max_color_value | ||
) |
void calibration::LoadCameraTargetBasedIntrinsicsCalibratorParams | ( | config_reader::ConfigReader & | config, |
CameraTargetBasedIntrinsicsCalibratorParams & | params | ||
) |
void calibration::LoadOptimizationParams | ( | config_reader::ConfigReader & | config, |
optimization_common::OptimizationParams & | params, | ||
const std::string & | prefix = "" |
||
) |
void calibration::LoadRansacPnPParams | ( | config_reader::ConfigReader & | config, |
vision_common::RansacPnPParams & | params | ||
) |
void calibration::LoadReprojectionPoseEstimateParams | ( | config_reader::ConfigReader & | config, |
vision_common::ReprojectionPoseEstimateParams & | params | ||
) |
void calibration::LoadRunCalibratorParams | ( | config_reader::ConfigReader & | config, |
RunCalibratorParams & | params | ||
) |
void calibration::LoadSolverOptions | ( | config_reader::ConfigReader & | config, |
ceres::Solver::Options & | solver_options, | ||
const std::string & | prefix = "" |
||
) |
cv::Mat calibration::MapImageColors | ( | const cv::Mat & | gray_image | ) |
void calibration::PrintCameraTTargetsStats | ( | const std::vector< MatchSet > & | match_sets, |
const std::vector< Eigen::Isometry3d > & | optimized_camera_T_targets | ||
) |
void calibration::SaveReprojectionFromAllTargetsImage | ( | const std::vector< Eigen::Isometry3d > & | camera_T_targets, |
const std::vector< localization_common::ImageCorrespondences > & | valid_match_sets, | ||
const Eigen::Matrix3d & | intrinsics, | ||
const Eigen::VectorXd & | distortion, | ||
const Eigen::Vector2i & | image_size, | ||
const double | max_visualization_error_norm = 100 |
||
) |
void calibration::SaveReprojectionImage | ( | const std::vector< Eigen::Vector2d > & | image_points, |
const std::vector< Eigen::Vector3d > & | points_3d, | ||
const std::vector< int > & | indices, | ||
const Eigen::Matrix3d & | intrinsics, | ||
const Eigen::VectorXd & | distortion, | ||
const Eigen::Isometry3d & | pose, | ||
const double | max_visualization_error_norm, | ||
const std::string & | name | ||
) |