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_2D_H_
00018 #define CARTOGRAPHER_MAPPING_INTERNAL_OPTIMIZATION_COST_FUNCTIONS_LANDMARK_COST_FUNCTION_2D_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_2d.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
00037 class LandmarkCostFunction2D {
00038 public:
00039 using LandmarkObservation =
00040 PoseGraphInterface::LandmarkNode::LandmarkObservation;
00041
00042 static ceres::CostFunction* CreateAutoDiffCostFunction(
00043 const LandmarkObservation& observation, const NodeSpec2D& prev_node,
00044 const NodeSpec2D& next_node) {
00045 return new ceres::AutoDiffCostFunction<
00046 LandmarkCostFunction2D, 6 ,
00047 3 , 3 ,
00048 4 ,
00049 3 >(
00050 new LandmarkCostFunction2D(observation, prev_node, next_node));
00051 }
00052
00053 template <typename T>
00054 bool operator()(const T* const prev_node_pose, const T* const next_node_pose,
00055 const T* const landmark_rotation,
00056 const T* const landmark_translation, T* const e) const {
00057 const std::tuple<std::array<T, 4>, std::array<T, 3>>
00058 interpolated_rotation_and_translation = InterpolateNodes2D(
00059 prev_node_pose, prev_node_gravity_alignment_, next_node_pose,
00060 next_node_gravity_alignment_, interpolation_parameter_);
00061 const std::array<T, 6> error = ScaleError(
00062 ComputeUnscaledError(
00063 landmark_to_tracking_transform_,
00064 std::get<0>(interpolated_rotation_and_translation).data(),
00065 std::get<1>(interpolated_rotation_and_translation).data(),
00066 landmark_rotation, landmark_translation),
00067 translation_weight_, rotation_weight_);
00068 std::copy(std::begin(error), std::end(error), e);
00069 return true;
00070 }
00071
00072 private:
00073 LandmarkCostFunction2D(const LandmarkObservation& observation,
00074 const NodeSpec2D& prev_node,
00075 const NodeSpec2D& next_node)
00076 : landmark_to_tracking_transform_(
00077 observation.landmark_to_tracking_transform),
00078 prev_node_gravity_alignment_(prev_node.gravity_alignment),
00079 next_node_gravity_alignment_(next_node.gravity_alignment),
00080 translation_weight_(observation.translation_weight),
00081 rotation_weight_(observation.rotation_weight),
00082 interpolation_parameter_(
00083 common::ToSeconds(observation.time - prev_node.time) /
00084 common::ToSeconds(next_node.time - prev_node.time)) {}
00085
00086 const transform::Rigid3d landmark_to_tracking_transform_;
00087 const Eigen::Quaterniond prev_node_gravity_alignment_;
00088 const Eigen::Quaterniond next_node_gravity_alignment_;
00089 const double translation_weight_;
00090 const double rotation_weight_;
00091 const double interpolation_parameter_;
00092 };
00093
00094 }
00095 }
00096 }
00097
00098 #endif // CARTOGRAPHER_MAPPING_INTERNAL_OPTIMIZATION_COST_FUNCTIONS_LANDMARK_COST_FUNCTION_2D_H_