landmark_cost_function_2d.h
Go to the documentation of this file.
1 /*
2  * Copyright 2018 The Cartographer Authors
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9  *
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  */
16 
17 #ifndef CARTOGRAPHER_MAPPING_INTERNAL_OPTIMIZATION_COST_FUNCTIONS_LANDMARK_COST_FUNCTION_2D_H_
18 #define CARTOGRAPHER_MAPPING_INTERNAL_OPTIMIZATION_COST_FUNCTIONS_LANDMARK_COST_FUNCTION_2D_H_
19 
20 #include "Eigen/Core"
21 #include "Eigen/Geometry"
27 #include "ceres/ceres.h"
28 #include "ceres/jet.h"
29 
30 namespace cartographer {
31 namespace mapping {
32 namespace optimization {
33 
34 // Cost function measuring the weighted error between the observed pose given by
35 // the landmark measurement and the linearly interpolated pose of embedded in 3D
36 // space node poses.
38  public:
39  using LandmarkObservation =
41 
42  static ceres::CostFunction* CreateAutoDiffCostFunction(
43  const LandmarkObservation& observation, const NodeSpec2D& prev_node,
44  const NodeSpec2D& next_node) {
45  return new ceres::AutoDiffCostFunction<
46  LandmarkCostFunction2D, 6 /* residuals */,
47  3 /* previous node pose variables */, 3 /* next node pose variables */,
48  4 /* landmark rotation variables */,
49  3 /* landmark translation variables */>(
50  new LandmarkCostFunction2D(observation, prev_node, next_node));
51  }
52 
53  template <typename T>
54  bool operator()(const T* const prev_node_pose, const T* const next_node_pose,
55  const T* const landmark_rotation,
56  const T* const landmark_translation, T* const e) const {
57  const std::tuple<std::array<T, 4>, std::array<T, 3>>
58  interpolated_rotation_and_translation = InterpolateNodes2D(
59  prev_node_pose, prev_node_gravity_alignment_, next_node_pose,
61  const std::array<T, 6> error = ScaleError(
64  std::get<0>(interpolated_rotation_and_translation).data(),
65  std::get<1>(interpolated_rotation_and_translation).data(),
66  landmark_rotation, landmark_translation),
68  std::copy(std::begin(error), std::end(error), e);
69  return true;
70  }
71 
72  private:
74  const NodeSpec2D& prev_node,
75  const NodeSpec2D& next_node)
77  observation.landmark_to_tracking_transform),
78  prev_node_gravity_alignment_(prev_node.gravity_alignment),
79  next_node_gravity_alignment_(next_node.gravity_alignment),
80  translation_weight_(observation.translation_weight),
81  rotation_weight_(observation.rotation_weight),
83  common::ToSeconds(observation.time - prev_node.time) /
84  common::ToSeconds(next_node.time - prev_node.time)) {}
85 
87  const Eigen::Quaterniond prev_node_gravity_alignment_;
88  const Eigen::Quaterniond next_node_gravity_alignment_;
89  const double translation_weight_;
90  const double rotation_weight_;
92 };
93 
94 } // namespace optimization
95 } // namespace mapping
96 } // namespace cartographer
97 
98 #endif // CARTOGRAPHER_MAPPING_INTERNAL_OPTIMIZATION_COST_FUNCTIONS_LANDMARK_COST_FUNCTION_2D_H_
LandmarkCostFunction2D(const LandmarkObservation &observation, const NodeSpec2D &prev_node, const NodeSpec2D &next_node)
static ceres::CostFunction * CreateAutoDiffCostFunction(const LandmarkObservation &observation, const NodeSpec2D &prev_node, const NodeSpec2D &next_node)
bool operator()(const T *const prev_node_pose, const T *const next_node_pose, const T *const landmark_rotation, const T *const landmark_translation, T *const e) const
static time_point time
std::array< T, 3 > ScaleError(const std::array< T, 3 > &error, double translation_weight, double rotation_weight)
double ToSeconds(const Duration duration)
Definition: time.cc:29
std::tuple< std::array< T, 4 >, std::array< T, 3 > > InterpolateNodes2D(const T *const prev_node_pose, const Eigen::Quaterniond &prev_node_gravity_alignment, const T *const next_node_pose, const Eigen::Quaterniond &next_node_gravity_alignment, const double interpolation_parameter)
static std::array< T, 3 > ComputeUnscaledError(const transform::Rigid2d &relative_pose, const T *const start, const T *const end)


cartographer
Author(s): The Cartographer Authors
autogenerated on Mon Feb 28 2022 22:00:58