17 #ifndef CARTOGRAPHER_MAPPING_3D_CERES_POSE_H_ 18 #define CARTOGRAPHER_MAPPING_3D_CERES_POSE_H_ 25 #include "ceres/ceres.h" 28 namespace mapping_3d {
34 std::unique_ptr<ceres::LocalParameterization> translation_parametrization,
35 std::unique_ptr<ceres::LocalParameterization> rotation_parametrization,
36 ceres::Problem* problem);
55 #endif // CARTOGRAPHER_MAPPING_3D_CERES_POSE_H_ std::array< double, 4 > rotation_
std::array< double, 3 > translation_
const transform::Rigid3d ToRigid() const
CeresPose(const transform::Rigid3d &rigid, std::unique_ptr< ceres::LocalParameterization > translation_parametrization, std::unique_ptr< ceres::LocalParameterization > rotation_parametrization, ceres::Problem *problem)
CeresPose & operator=(const CeresPose &)=delete