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_LANDMARK_COST_FUNCTION_3D_H_
00018 #define CARTOGRAPHER_MAPPING_INTERNAL_OPTIMIZATION_COST_FUNCTIONS_LANDMARK_COST_FUNCTION_3D_H_
00019
00020 #include "Eigen/Core"
00021 #include "Eigen/Geometry"
00022 #include "cartographer/mapping/internal/optimization/cost_functions/cost_helpers.h"
00023 #include "cartographer/mapping/internal/optimization/optimization_problem_3d.h"
00024 #include "cartographer/mapping/pose_graph_interface.h"
00025 #include "cartographer/transform/rigid_transform.h"
00026 #include "cartographer/transform/transform.h"
00027 #include "ceres/ceres.h"
00028 #include "ceres/jet.h"
00029
00030 namespace cartographer {
00031 namespace mapping {
00032 namespace optimization {
00033
00034
00035
00036 class LandmarkCostFunction3D {
00037 public:
00038 using LandmarkObservation =
00039 PoseGraphInterface::LandmarkNode::LandmarkObservation;
00040
00041 static ceres::CostFunction* CreateAutoDiffCostFunction(
00042 const LandmarkObservation& observation, const NodeSpec3D& prev_node,
00043 const NodeSpec3D& next_node) {
00044 return new ceres::AutoDiffCostFunction<
00045 LandmarkCostFunction3D, 6 ,
00046 4 ,
00047 3 ,
00048 4 ,
00049 3 ,
00050 4 ,
00051 3 >(
00052 new LandmarkCostFunction3D(observation, prev_node, next_node));
00053 }
00054
00055 template <typename T>
00056 bool operator()(const T* const prev_node_rotation,
00057 const T* const prev_node_translation,
00058 const T* const next_node_rotation,
00059 const T* const next_node_translation,
00060 const T* const landmark_rotation,
00061 const T* const landmark_translation, T* const e) const {
00062 const std::tuple<std::array<T, 4>, std::array<T, 3>>
00063 interpolated_rotation_and_translation = InterpolateNodes3D(
00064 prev_node_rotation, prev_node_translation, next_node_rotation,
00065 next_node_translation, interpolation_parameter_);
00066 const std::array<T, 6> error = ScaleError(
00067 ComputeUnscaledError(
00068 landmark_to_tracking_transform_,
00069 std::get<0>(interpolated_rotation_and_translation).data(),
00070 std::get<1>(interpolated_rotation_and_translation).data(),
00071 landmark_rotation, landmark_translation),
00072 translation_weight_, rotation_weight_);
00073 std::copy(std::begin(error), std::end(error), e);
00074 return true;
00075 }
00076
00077 private:
00078 LandmarkCostFunction3D(const LandmarkObservation& observation,
00079 const NodeSpec3D& prev_node,
00080 const NodeSpec3D& next_node)
00081 : landmark_to_tracking_transform_(
00082 observation.landmark_to_tracking_transform),
00083 translation_weight_(observation.translation_weight),
00084 rotation_weight_(observation.rotation_weight),
00085 interpolation_parameter_(
00086 common::ToSeconds(observation.time - prev_node.time) /
00087 common::ToSeconds(next_node.time - prev_node.time)) {}
00088
00089 const transform::Rigid3d landmark_to_tracking_transform_;
00090 const double translation_weight_;
00091 const double rotation_weight_;
00092 const double interpolation_parameter_;
00093 };
00094
00095 }
00096 }
00097 }
00098
00099 #endif // CARTOGRAPHER_MAPPING_INTERNAL_OPTIMIZATION_COST_FUNCTIONS_LANDMARK_COST_FUNCTION_3D_H_