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_COST_FUNCTIONS_SPA_COST_FUNCTION_3D_H_
00018 #define CARTOGRAPHER_MAPPING_INTERNAL_OPTIMIZATION_COST_FUNCTIONS_SPA_COST_FUNCTION_3D_H_
00019
00020 #include <array>
00021
00022 #include "Eigen/Core"
00023 #include "Eigen/Geometry"
00024 #include "cartographer/common/math.h"
00025 #include "cartographer/mapping/internal/optimization/cost_functions/cost_helpers.h"
00026 #include "cartographer/mapping/pose_graph.h"
00027 #include "cartographer/transform/rigid_transform.h"
00028 #include "cartographer/transform/transform.h"
00029 #include "ceres/ceres.h"
00030 #include "ceres/jet.h"
00031
00032 namespace cartographer {
00033 namespace mapping {
00034 namespace optimization {
00035
00036 class SpaCostFunction3D {
00037 public:
00038 static ceres::CostFunction* CreateAutoDiffCostFunction(
00039 const PoseGraph::Constraint::Pose& pose) {
00040 return new ceres::AutoDiffCostFunction<
00041 SpaCostFunction3D, 6 , 4 ,
00042 3 , 4 ,
00043 3 >(new SpaCostFunction3D(pose));
00044 }
00045
00046 template <typename T>
00047 bool operator()(const T* const c_i_rotation, const T* const c_i_translation,
00048 const T* const c_j_rotation, const T* const c_j_translation,
00049 T* const e) const {
00050 const std::array<T, 6> error = ScaleError(
00051 ComputeUnscaledError(pose_.zbar_ij, c_i_rotation, c_i_translation,
00052 c_j_rotation, c_j_translation),
00053 pose_.translation_weight, pose_.rotation_weight);
00054 std::copy(std::begin(error), std::end(error), e);
00055 return true;
00056 }
00057
00058 private:
00059 explicit SpaCostFunction3D(const PoseGraph::Constraint::Pose& pose)
00060 : pose_(pose) {}
00061
00062 const PoseGraph::Constraint::Pose pose_;
00063 };
00064
00065 }
00066 }
00067 }
00068
00069 #endif // CARTOGRAPHER_MAPPING_INTERNAL_OPTIMIZATION_COST_FUNCTIONS_SPA_COST_FUNCTION_3D_H_