Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017 #ifndef CARTOGRAPHER_MAPPING_INTERNAL_OPTIMIZATION_CERES_POSE_H_
00018 #define CARTOGRAPHER_MAPPING_INTERNAL_OPTIMIZATION_CERES_POSE_H_
00019
00020 #include <array>
00021 #include <memory>
00022
00023 #include "Eigen/Core"
00024 #include "cartographer/transform/rigid_transform.h"
00025 #include "ceres/ceres.h"
00026
00027 namespace cartographer {
00028 namespace mapping {
00029 namespace optimization {
00030
00031 class CeresPose {
00032 public:
00033 CeresPose(
00034 const transform::Rigid3d& rigid,
00035 std::unique_ptr<ceres::LocalParameterization> translation_parametrization,
00036 std::unique_ptr<ceres::LocalParameterization> rotation_parametrization,
00037 ceres::Problem* problem);
00038
00039 const transform::Rigid3d ToRigid() const;
00040
00041 double* translation() { return data_->translation.data(); }
00042 const double* translation() const { return data_->translation.data(); }
00043
00044 double* rotation() { return data_->rotation.data(); }
00045 const double* rotation() const { return data_->rotation.data(); }
00046
00047 struct Data {
00048 std::array<double, 3> translation;
00049
00050 std::array<double, 4> rotation;
00051 };
00052
00053 Data& data() { return *data_; }
00054
00055 private:
00056 std::shared_ptr<Data> data_;
00057 };
00058
00059 CeresPose::Data FromPose(const transform::Rigid3d& pose);
00060
00061 }
00062 }
00063 }
00064
00065 #endif // CARTOGRAPHER_MAPPING_INTERNAL_OPTIMIZATION_CERES_POSE_H_