17 #ifndef CARTOGRAPHER_MAPPING_INTERNAL_OPTIMIZATION_CERES_POSE_H_ 18 #define CARTOGRAPHER_MAPPING_INTERNAL_OPTIMIZATION_CERES_POSE_H_ 25 #include "ceres/ceres.h" 29 namespace optimization {
35 std::unique_ptr<ceres::LocalParameterization> translation_parametrization,
36 std::unique_ptr<ceres::LocalParameterization> rotation_parametrization,
37 ceres::Problem* problem);
65 #endif // CARTOGRAPHER_MAPPING_INTERNAL_OPTIMIZATION_CERES_POSE_H_ std::array< double, 4 > rotation
CeresPose(const transform::Rigid3d &rigid, std::unique_ptr< ceres::LocalParameterization > translation_parametrization, std::unique_ptr< ceres::LocalParameterization > rotation_parametrization, ceres::Problem *problem)
CeresPose::Data FromPose(const transform::Rigid3d &pose)
std::shared_ptr< Data > data_
const double * rotation() const
const transform::Rigid3d ToRigid() const
const double * translation() const
std::array< double, 3 > translation