NASA Astrobee Robot Software
0.19.1
Flight software for the Astrobee robots operating inside the International Space Station.
|
#include <Eigen/Core>
#include <ceres/ceres.h>
#include <ceres/rotation.h>
#include <vector>
Go to the source code of this file.
Namespaces | |
optimization_common | |
Functions | |
template<typename T > | |
Eigen::Matrix< T, 6, 1 > | optimization_common::VectorFromIsometry3 (const Eigen::Transform< T, 3, Eigen::Isometry > &isometry_3) |
Eigen::Matrix< double, 6, 1 > | optimization_common::VectorFromIsometry3d (const Eigen::Isometry3d &isometry_3d) |
Eigen::Matrix< double, 7, 1 > | optimization_common::VectorFromAffine3d (const Eigen::Affine3d &affine_3d) |
template<typename T > | |
Eigen::Transform< T, 3, Eigen::Isometry > | optimization_common::Isometry3 (const T *isometry_data) |
Eigen::Matrix3d | optimization_common::Intrinsics (const Eigen::Vector2d &focal_lengths, const Eigen::Vector2d &principal_points) |
template<typename T > | |
Eigen::Transform< T, 3, Eigen::Affine > | optimization_common::Affine3 (const T *affine_data) |
Eigen::Isometry3d | optimization_common::Isometry3d (const Eigen::Matrix< double, 6, 1 > &isometry_vector) |
Eigen::Affine3d | optimization_common::Affine3d (const Eigen::Matrix< double, 7, 1 > &affine_vector) |
template<typename T > | |
Eigen::Matrix< T, 3, 3 > | optimization_common::Intrinsics (const T *intrinsics_data) |
template<typename T > | |
Eigen::Matrix< T, 3, 3 > | optimization_common::Intrinsics (const T *focal_lengths, const T *principal_points) |
void | optimization_common::AddParameterBlock (const int num_parameters, double *const parameters, ceres::Problem &problem, const bool set_constant=false) |
void | optimization_common::AddConstantParameterBlock (const int num_parameters, double *const parameters, ceres::Problem &problem) |
void | optimization_common::AddConstantParameterBlock (const int num_parameters, double const *const parameters, ceres::Problem &problem) |
double | optimization_common::ResidualNorm (const std::vector< double > &residual, const int index, const int residual_size) |
void | optimization_common::CheckResiduals (const int residual_size, ceres::Problem &problem, const double outlier_threshold=0.99) |